|
48 | 48 | #include <nav_msgs/Odometry.h> |
49 | 49 | #include <geometry_msgs/Twist.h> |
50 | 50 | #include <rosgraph_msgs/Clock.h> |
| 51 | +#include <geometry_msgs/Pose2D.h> |
51 | 52 |
|
52 | 53 | #include <std_srvs/Empty.h> |
53 | 54 |
|
|
61 | 62 | #define BASE_SCAN "base_scan" |
62 | 63 | #define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth" |
63 | 64 | #define CMD_VEL "cmd_vel" |
| 65 | +#define POSE "pose" |
64 | 66 |
|
65 | 67 | // Our node |
66 | 68 | class StageNode |
@@ -96,6 +98,7 @@ class StageNode |
96 | 98 | std::vector<ros::Publisher> laser_pubs; //multiple lasers |
97 | 99 |
|
98 | 100 | ros::Subscriber cmdvel_sub; //one cmd_vel subscriber |
| 101 | + ros::Subscriber pose_sub; //one pos subscriber |
99 | 102 | }; |
100 | 103 |
|
101 | 104 | std::vector<StageRobot const *> robotmodels_; |
@@ -161,6 +164,9 @@ class StageNode |
161 | 164 | // Message callback for a MsgBaseVel message, which set velocities. |
162 | 165 | void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg); |
163 | 166 |
|
| 167 | + // Message callback for a Pose2D message, which sets pose. |
| 168 | + void poseReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg); |
| 169 | + |
164 | 170 | // Service callback for soft reset |
165 | 171 | bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response); |
166 | 172 |
|
@@ -266,6 +272,18 @@ StageNode::cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist |
266 | 272 | this->base_last_cmd = this->sim_time; |
267 | 273 | } |
268 | 274 |
|
| 275 | +void |
| 276 | +StageNode::poseReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg) |
| 277 | +{ |
| 278 | + boost::mutex::scoped_lock lock(msg_lock); |
| 279 | + Stg::Pose pose; |
| 280 | + pose.x = msg->x; |
| 281 | + pose.y = msg->y; |
| 282 | + pose.z =0; |
| 283 | + pose.a = msg->theta; |
| 284 | + this->positionmodels[idx]->SetPose(pose); |
| 285 | +} |
| 286 | + |
269 | 287 | StageNode::StageNode(int argc, char** argv, bool gui, const char* fname, bool use_model_names) |
270 | 288 | { |
271 | 289 | this->use_model_names = use_model_names; |
@@ -354,6 +372,7 @@ StageNode::SubscribeModels() |
354 | 372 | new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10); |
355 | 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); |
356 | 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)); |
357 | 376 |
|
358 | 377 | for (size_t s = 0; s < new_robot->lasermodels.size(); ++s) |
359 | 378 | { |
@@ -734,6 +753,8 @@ StageNode::WorldCallback() |
734 | 753 | int |
735 | 754 | main(int argc, char** argv) |
736 | 755 | { |
| 756 | + ROS_INFO_STREAM("Custom stage_ros by MAK."); |
| 757 | + |
737 | 758 | if( argc < 2 ) |
738 | 759 | { |
739 | 760 | puts(USAGE); |
|
0 commit comments