|
50 | 50 | #include <nav_msgs/Odometry.h> |
51 | 51 | #include <geometry_msgs/Twist.h> |
52 | 52 | #include <rosgraph_msgs/Clock.h> |
| 53 | +#include <geometry_msgs/Pose2D.h> |
53 | 54 |
|
54 | 55 | #include <std_srvs/Empty.h> |
55 | 56 |
|
|
72 | 73 | #define BASE_MARKER_DETECTION "base_marker_detection" |
73 | 74 | #define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth" |
74 | 75 | #define CMD_VEL "cmd_vel" |
| 76 | +#define CMD_POSE "cmd_pose" |
75 | 77 | #define NUM_DETECTORS 5 |
76 | 78 | static char * detectors[] = {"detector", "robot_detector", "victim_detector", "marker_detector", "debris_detector"}; |
77 | 79 |
|
@@ -120,6 +122,7 @@ class StageNode |
120 | 122 | std::vector<ros::Publisher> fiducial_pubs; //multiple fiducials |
121 | 123 |
|
122 | 124 | ros::Subscriber cmdvel_sub; //one cmd_vel subscriber |
| 125 | + ros::Subscriber cmdpose_sub; //one pos subscriber |
123 | 126 |
|
124 | 127 | VelocityCmdsDiffDrive cmdsDes; |
125 | 128 | }; |
@@ -197,7 +200,10 @@ class StageNode |
197 | 200 |
|
198 | 201 | // Message callback for a MsgBaseVel message, which set velocities. |
199 | 202 | void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg); |
200 | | - |
| 203 | + |
| 204 | + // Message callback for a Pose2D message, which sets pose. |
| 205 | + void cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg); |
| 206 | + |
201 | 207 | void cmdvelReceivedConstrainedDiffDrive(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg); |
202 | 208 |
|
203 | 209 | // Service callback for soft reset |
@@ -356,6 +362,18 @@ StageNode::ghfunc(Stg::Model* mod, StageNode* node) |
356 | 362 |
|
357 | 363 |
|
358 | 364 |
|
| 365 | +void |
| 366 | +StageNode::cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg) |
| 367 | +{ |
| 368 | + boost::mutex::scoped_lock lock(msg_lock); |
| 369 | + Stg::Pose pose; |
| 370 | + pose.x = msg->x; |
| 371 | + pose.y = msg->y; |
| 372 | + pose.z =0; |
| 373 | + pose.a = msg->theta; |
| 374 | + this->positionmodels[idx]->SetPose(pose); |
| 375 | +} |
| 376 | + |
359 | 377 | bool |
360 | 378 | StageNode::cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) |
361 | 379 | { |
@@ -488,6 +506,8 @@ StageNode::SubscribeModels() |
488 | 506 |
|
489 | 507 | new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10); |
490 | 508 | new_robot->ground_truth_pub = n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10); |
| 509 | + 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)); |
| 510 | + |
491 | 511 | if(!config_.constrainedDiffDrive) { |
492 | 512 | 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)); |
493 | 513 | } else { |
@@ -624,8 +644,6 @@ StageNode::WorldCallback() |
624 | 644 | this->positionmodels[i]->SetSpeed(vAns, 0, wAns); |
625 | 645 | } |
626 | 646 | } |
627 | | - |
628 | | - |
629 | 647 |
|
630 | 648 | this->sim_time.fromSec(world->SimTimeNow() / 1e6); |
631 | 649 | // We're not allowed to publish clock==0, because it used as a special |
|
0 commit comments