|
62 | 62 | #define BASE_SCAN "base_scan" |
63 | 63 | #define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth" |
64 | 64 | #define CMD_VEL "cmd_vel" |
65 | | -#define POSE "pose" |
| 65 | +#define CMD_POSE "cmd_pose" |
66 | 66 |
|
67 | 67 | // Our node |
68 | 68 | class StageNode |
@@ -98,7 +98,7 @@ class StageNode |
98 | 98 | std::vector<ros::Publisher> laser_pubs; //multiple lasers |
99 | 99 |
|
100 | 100 | ros::Subscriber cmdvel_sub; //one cmd_vel subscriber |
101 | | - ros::Subscriber pose_sub; //one pos subscriber |
| 101 | + ros::Subscriber cmdpose_sub; //one pos subscriber |
102 | 102 | }; |
103 | 103 |
|
104 | 104 | std::vector<StageRobot const *> robotmodels_; |
@@ -165,7 +165,7 @@ class StageNode |
165 | 165 | void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg); |
166 | 166 |
|
167 | 167 | // Message callback for a Pose2D message, which sets pose. |
168 | | - void poseReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg); |
| 168 | + void cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg); |
169 | 169 |
|
170 | 170 | // Service callback for soft reset |
171 | 171 | bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response); |
@@ -273,7 +273,7 @@ StageNode::cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist |
273 | 273 | } |
274 | 274 |
|
275 | 275 | void |
276 | | -StageNode::poseReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg) |
| 276 | +StageNode::cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg) |
277 | 277 | { |
278 | 278 | boost::mutex::scoped_lock lock(msg_lock); |
279 | 279 | Stg::Pose pose; |
@@ -372,7 +372,7 @@ StageNode::SubscribeModels() |
372 | 372 | new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10); |
373 | 373 | new_robot->ground_truth_pub = n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10); |
374 | 374 | new_robot->cmdvel_sub = n_.subscribe<geometry_msgs::Twist>(mapName(CMD_VEL, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdvelReceived, this, r, _1)); |
375 | | - new_robot->pose_sub = n_.subscribe<geometry_msgs::Pose2D>(mapName(POSE, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::poseReceived, this, r, _1)); |
| 375 | + new_robot->cmdpose_sub = n_.subscribe<geometry_msgs::Pose2D>(mapName(CMD_POSE, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdposeReceived, this, r, _1)); |
376 | 376 |
|
377 | 377 | for (size_t s = 0; s < new_robot->lasermodels.size(); ++s) |
378 | 378 | { |
@@ -753,7 +753,7 @@ StageNode::WorldCallback() |
753 | 753 | int |
754 | 754 | main(int argc, char** argv) |
755 | 755 | { |
756 | | - ROS_INFO_STREAM("Custom stage_ros by MAK."); |
| 756 | + ROS_INFO_STREAM("Command robot pose programmatically by publishing a geometry_msgs/Pose2D to /pose (single robot) or /robot_#/pose (multiple robots). -MAK"); |
757 | 757 |
|
758 | 758 | if( argc < 2 ) |
759 | 759 | { |
|
0 commit comments