Node unable to subscribe the specified topic
Specification: Ubuntu 16.04, ROS kinetic, Gazebo, turtlebot3
Here is my rqt_graph
There is a node /negotiator
which should subscribe cca_cmd_vel
and publish to cmd_vel
.
turtlebot3_teleop_keyboard
and move_base
publish on cca_cmd_vel
.
Here is the code
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
void cca_cmd_velCallback(const geometry_msgs::Twist::ConstPtr& vel)
{
geometry_msgs::Twist new_vel = *vel;
cmd_vel_pub.publish(new_vel);
}
int main(int argc, char **argv)
{
//Negotiator Subscribe cmd_vel
ros::init(argc, argv, "negotiator");
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("cca_cmd_vel", 1000, cca_cmd_velCallback);
//Negotiator Publish to GAZEBO
ros::Publisher cmd_vel_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
//ros::Publisher cmd_vel_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
ros::spin();
return 0;
}
Kindly suggest where to improve
Few More add on information
crlab@crlab-500-100IX:~$ rostopic info cca_cmd_vel
Type: geometry_msgs/Twist
Publishers:
* /move_base (http://localhost:34459/)
* /turtlebot3_teleop_keyboard (http://localhost:41875/)
Subscribers: None
crlab@crlab-500-100IX:~$ rostopic info cmd_vel
Type: geometry_msgs/Twist
Publishers: None
Subscribers:
* /gazebo (http://localhost:33175/)
* /negotiator (http://localhost:35659/)
crlab@crlab-500-100IX:~$ rosnode info negotiator
--------------------------------------------------------------------------------
Node [/negotiator]
Publications:
* /rosout [rosgraph_msgs/Log]
Subscriptions:
* /clock [rosgraph_msgs/Clock]
* /cmd_vel [unknown type]
Services:
* /negotiator/get_loggers
* /negotiator/set_logger_level
contacting node http://localhost:35659/ ...
Pid: 4967
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
* topic: /clock
* to: /gazebo (http://localhost:33175/)
* direction: inbound
* transport: TCPROS
crlab@crlab-500-100IX:~$ rosnode info turtlebot3_teleop_keyboard
--------------------------------------------------------------------------------
Node [/turtlebot3_teleop_keyboard]
Publications:
* /cca_cmd_vel [geometry_msgs/Twist]
* /rosout [rosgraph_msgs/Log]
Subscriptions:
* /clock [rosgraph_msgs/Clock]
Services:
* /turtlebot3_teleop_keyboard/get_loggers
* /turtlebot3_teleop_keyboard/set_logger_level
contacting node http://localhost:41875/ ...
Pid: 4938
Connections:
* topic: /rosout
* to: /rosout
* direction: outbound
* transport: TCPROS
* topic: /clock
* to: /gazebo (http://localhost:33175/)
* direction: inbound
* transport: TCPROS
crlab@crlab-500-100IX:~$ rosnode info move_base
Node [/move_base]
Publications:
* /cca_cmd_vel [geometry_msgs/Twist]
* /move_base/DWAPlannerROS/cost_cloud [sensor_msgs/PointCloud2]
* /move_base/DWAPlannerROS/global_plan [nav_msgs/Path]
* /move_base/DWAPlannerROS/local_plan [nav_msgs/Path]
* /move_base/DWAPlannerROS/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/DWAPlannerROS/parameter_updates [dynamic_reconfigure/Config]
* /move_base/DWAPlannerROS/trajectory_cloud [sensor_msgs/PointCloud2]
* /move_base/NavfnROS/plan [nav_msgs/Path]
* /move_base/current_goal [geometry_msgs/PoseStamped]
* /move_base/feedback [move_base_msgs/MoveBaseActionFeedback]
* /move_base/global_costmap/costmap [nav_msgs/OccupancyGrid]
* /move_base/global_costmap/costmap_updates [map_msgs/OccupancyGridUpdate]
* /move_base/global_costmap/footprint [geometry_msgs/PolygonStamped]
* /move_base/global_costmap/inflation_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/global_costmap/inflation_layer/parameter_updates [dynamic_reconfigure/Config]
* /move_base/global_costmap/obstacle_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/global_costmap/obstacle_layer/parameter_updates [dynamic_reconfigure/Config]
* /move_base/global_costmap/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/global_costmap/parameter_updates [dynamic_reconfigure/Config]
* /move_base/global_costmap/static_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/global_costmap/static_layer/parameter_updates [dynamic_reconfigure/Config]
* /move_base/goal [move_base_msgs/MoveBaseActionGoal]
* /move_base/local_costmap/costmap [nav_msgs/OccupancyGrid]
* /move_base/local_costmap/costmap_updates [map_msgs/OccupancyGridUpdate]
* /move_base/local_costmap/footprint [geometry_msgs/PolygonStamped]
* /move_base/local_costmap/inflation_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/local_costmap/inflation_layer/parameter_updates [dynamic_reconfigure/Config]
* /move_base/local_costmap/obstacle_layer/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/local_costmap/obstacle_layer/parameter_updates [dynamic_reconfigure/Config]
* /move_base/local_costmap/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/local_costmap/parameter_updates [dynamic_reconfigure/Config]
* /move_base/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
* /move_base/parameter_updates [dynamic_reconfigure/Config]
* /move_base/result [move_base_msgs/MoveBaseActionResult]
* /move_base/status [actionlib_msgs/GoalStatusArray]
* /rosout [rosgraph_msgs/Log]
Subscriptions:
* /clock [rosgraph_msgs/Clock]
* /map [nav_msgs/OccupancyGrid]
* /move_base/cancel [unknown type]
* /move_base/global_costmap/footprint [geometry_msgs/PolygonStamped]
* /move_base/goal [move_base_msgs/MoveBaseActionGoal]
* /move_base/local_costmap/footprint [geometry_msgs/PolygonStamped]
* /move_base_simple/goal [geometry_msgs/PoseStamped]
* /odom [nav_msgs/Odometry]
* /scan [sensor_msgs/LaserScan]
* /tf [tf2_msgs/TFMessage]
* /tf_static [tf2_msgs/TFMessage]
Services:
* /move_base/DWAPlannerROS/set_parameters
* /move_base/NavfnROS/make_plan
* /move_base/clear_costmaps
* /move_base/get_loggers
* /move_base/global_costmap/inflation_layer/set_parameters
* /move_base/global_costmap/obstacle_layer ...
How are you launching your nodes, maybe you can post the launch files as well. From the negotiator node you have posted you don't seem to do anything other than republishing the messages as a different topic, do you have plans to add some processing on the input? If you don't need processing on the topic, then you do not need a node to use a different topic name, you could just use the remap tag to change the topic when launching the publishing or subscribing node.
Roslaunch xml documentation
You can search this forum for examples on how to remap topics.
Seeing the output of
rostopic info cmd_vel
it looks like the negotiator is subscribing to cmd_vel, which is really weird since the code clearly states differently. Something in either your launch files or the posted code can't be correct. Are you already remapping cca_cmd_vle to cmd_vel?@Reamees I am executing node through
Once I can republish the data , I will later do some processing.
@LeoE 1. Whatever I have copied is correct. 2. This is the first node I am writing. There is no other remapping taking place.
Well there are no publishers in your negotiator node, and the "wrong" subscriber. Please try to delete your build and devel folder, rebuild your project and try it again. If the code is correct there must be a problem in either building or running the node. It could be, that an old version of your node is still somewhere in the system an is actually launched instead of the new one. Have you had the negotiator node subscribe to the cmd_vel topic before?