ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

how to add a subscriber in keyboard teleop ?

asked 2011-12-11 14:08:11 -0500

maruchi gravatar image

updated 2014-01-28 17:10:58 -0500

ngrennan gravatar image

Hi, I have an incomplete C++ code which intends to add a subscriber to get state from robot model. Due to my limited knowledge, I can not proceed on the below code. What I want from this code is to get robot states ("base_pose_ground_truth":position and velocity) and put a simple proportional trajectory following controller for a desired trajectory (double desired_pos = 15 * sin(ros::Time::now().toSec());).

During compiling it, I have the error messages:

.../src/keyboard.cpp:113:17: error: cannot convert ‘ros::Subscriber’ to ‘double’ in assignment

.../src/keyboard.cpp:117:45: error: ‘max_force’ cannot be used as a function

.../src/keyboard.cpp:118:45: error: ‘max_force’ cannot be used as a function

----The below is the incomplete C++ code -------------------

#include <termios.h>
#include <signal.h>
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/poll.h>

#include <boost/thread/thread.hpp>
#include <ros/ros.h>
#include <geometry_msgs/Wrench.h>
#include <nav_msgs/Odometry.h>


class ErraticKeyboardTeleopNode
{
    private:
        double thrust_;

        geometry_msgs::Wrench box_force_;
        nav_msgs::Odometry states_;
        ros::NodeHandle n_;
        ros::Publisher pub_;
        ros::Subscriber sub_;

    public:
        ErraticKeyboardTeleopNode()
        {
            pub_ = n_.advertise<geometry_msgs::Wrench>("box_force", 1);

            ros::NodeHandle n_private("~");
            n_private.param("thrust", thrust_, 30.0);
        }

        ~ErraticKeyboardTeleopNode() { }
        void keyboardLoop();

        void stopRobot()
        {
            box_force_.force.x = 0.0;
            box_force_.force.y = 0.0;
            box_force_.force.z = 0.0;
            pub_.publish(box_force_);
        }
};

ErraticKeyboardTeleopNode* tbk;
int kfd = 0;
struct termios cooked, raw;
bool done;

int main(int argc, char** argv)
{
    ros::init(argc,argv,"tbk", ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
    ErraticKeyboardTeleopNode tbk;

    boost::thread t = boost::thread(boost::bind(&ErraticKeyboardTeleopNode::keyboardLoop, &tbk));

    ros::spin();

    t.interrupt();
    t.join();
    tbk.stopRobot();
    tcsetattr(kfd, TCSANOW, &cooked);

    return(0);
}

void ErraticKeyboardTeleopNode::keyboardLoop()
{

    double max_force = thrust_;
    double current_pos;


    for(;;)
    {
        boost::this_thread::interruption_point();


        ros::Subscriber base_pose_sub_ = n_.subscribe<nav_msgs::Odometry> ("base_pose_ground_truth", 15, &ErraticKeyboardTeleopNode::keyboardLoop, this);

  double desired_pos = 15 * sin(ros::Time::now().toSec());
  current_pos = base_pose_sub_;
  max_force = -10 * (current_pos - desired_pos);


        box_force_.force.x = 1 * max_force(4);
        box_force_.force.y = 1 * max_force(5);
        box_force_.force.z = 0;
        pub_.publish(box_force_);
    }
}
edit retag flag offensive close merge delete

Comments

Firstly, keyboard_teleop base having a subscriber is not meaningful. It should generally publish something like velocity, acceleration and actions. And i don't think you can have 2 node_handlers for a single node. Errors in code are not from this code i guess as i don see those line numbers here.
karthik gravatar image karthik  ( 2011-12-16 06:51:28 -0500 )edit
Regarding general idea of using 2 nodehandlers, i have posted the question here, if you may want to check it. http://answers.ros.org/question/3343/is-it-possible-to-have-2-nodehandlers-for-a-single . It would be help people address your question if u attach the erroneous code here and ur idea.
karthik gravatar image karthik  ( 2011-12-16 06:58:03 -0500 )edit
Sorry, regarding the multi node_handlers, you can have them. But explain your idea and the attach the code that gave u error.
karthik gravatar image karthik  ( 2011-12-16 07:44:21 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2011-12-11 20:14:36 -0500

felix k gravatar image

updated 2011-12-11 20:16:15 -0500

The callback that you point to in the NodeHandle.subscribe(...) parameter has to be a separate callback method. It will be called every time a message is received. In that you may want to store the message (or its value) in a global variable which is read by the method needing that value.

Doc: http://www.ros.org/wiki/roscpp/Overview/Publishers%20and%20Subscribers#Subscriber_Options

Tut: http://www.ros.org/wiki/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2011-12-11 14:08:11 -0500

Seen: 3,067 times

Last updated: Dec 11 '11