Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add reset_positions service to stage #19

Merged
merged 2 commits into from
Jun 1, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ find_package(catkin REQUIRED
roscpp
sensor_msgs
std_msgs
std_srvs
tf
)

Expand Down
4 changes: 3 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<build_depend>sensor_msgs</build_depend>
<build_depend>stage</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>tf</build_depend>

<run_depend>boost</run_depend>
Expand All @@ -35,5 +36,6 @@
<run_depend>sensor_msgs</run_depend>
<run_depend>stage</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>tf</run_depend>
</package>
</package>
38 changes: 35 additions & 3 deletions src/stageros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@
#include <geometry_msgs/Twist.h>
#include <rosgraph_msgs/Clock.h>

#include <std_srvs/Empty.h>

#include "tf/transform_broadcaster.h"

#define USAGE "stageros <worldfile>"
Expand Down Expand Up @@ -98,7 +100,10 @@ class StageNode

std::vector<StageRobot const *> robotmodels_;


// Used to remember initial poses for soft reset
std::vector<Stg::Pose> initial_poses;
ros::ServiceServer reset_srv_;

ros::Publisher clock_pub_;

bool isDepthCanonical;
Expand Down Expand Up @@ -156,6 +161,9 @@ class StageNode
// Message callback for a MsgBaseVel message, which set velocities.
void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);

// Service callback for soft reset
bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);

// The main simulator object
Stg::World* world;
};
Expand Down Expand Up @@ -222,12 +230,32 @@ StageNode::ghfunc(Stg::Model* mod, StageNode* node)
{
if (dynamic_cast<Stg::ModelRanger *>(mod))
node->lasermodels.push_back(dynamic_cast<Stg::ModelRanger *>(mod));
if (dynamic_cast<Stg::ModelPosition *>(mod))
node->positionmodels.push_back(dynamic_cast<Stg::ModelPosition *>(mod));
if (dynamic_cast<Stg::ModelPosition *>(mod)) {
Stg::ModelPosition * p = dynamic_cast<Stg::ModelPosition *>(mod);
// remember initial poses
node->positionmodels.push_back(p);
node->initial_poses.push_back(p->GetGlobalPose());
}
if (dynamic_cast<Stg::ModelCamera *>(mod))
node->cameramodels.push_back(dynamic_cast<Stg::ModelCamera *>(mod));
}




bool
StageNode::cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
{
ROS_INFO("Resetting stage!");
for (size_t r = 0; r < this->positionmodels.size(); r++) {
this->positionmodels[r]->SetPose(this->initial_poses[r]);
this->positionmodels[r]->SetStall(false);
}
return true;
}



void
StageNode::cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg)
{
Expand Down Expand Up @@ -355,6 +383,10 @@ StageNode::SubscribeModels()
this->robotmodels_.push_back(new_robot);
}
clock_pub_ = n_.advertise<rosgraph_msgs::Clock>("/clock", 10);

// advertising reset service
reset_srv_ = n_.advertiseService("reset_positions", &StageNode::cb_reset_srv, this);

return(0);
}

Expand Down