Skip to content
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
8 changes: 6 additions & 2 deletions include/cartesian_interface/ros/RosExecutor.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,9 @@ namespace XBot { namespace Cartesian {
bool reset_joints_callback(cartesian_interface::ResetJointsRequest& req,
cartesian_interface::ResetJointsResponse& res);

bool pause_cartesio_callback(std_srvs::SetBoolRequest& req,
std_srvs::SetBoolRequest& res);

void timer_callback(const ros::TimerEvent& timer_ev);

void publish_fb_cmd_vel();
Expand Down Expand Up @@ -100,14 +103,15 @@ namespace XBot { namespace Cartesian {
ros::ServiceServer _loader_srv;
ros::ServiceServer _reset_srv;
ros::ServiceServer _reset_joints_srv;
ros::ServiceServer _pause_ci_srv;
ros::Subscriber _fb_sub;

ros::Timer _loop_timer;
double _time, _period;

MatLogger2::Ptr _logger;


bool _pause_command;

};

Expand Down
25 changes: 24 additions & 1 deletion src/ros/RosExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,9 @@ void RosExecutor::init_ros()
_reset_srv = _nh.advertiseService("reset", &RosExecutor::reset_callback, this);
_reset_joints_srv = _nh.advertiseService("reset_joints", &RosExecutor::reset_joints_callback, this);

/* Pause Cartesio to publish commands */
_pause_ci_srv = _nh.advertiseService("pause", &RosExecutor::pause_cartesio_callback, this);

/* Floating base override topic */
ros::NodeHandle nh_fb_queue(_nh);
nh_fb_queue.setCallbackQueue(&_fb_queue);
Expand Down Expand Up @@ -84,6 +87,7 @@ void RosExecutor::init_load_config()

_period = 1.0 / _nh_priv.param("rate", 100.0);

_pause_command = false;
}

void RosExecutor::init_load_robot()
Expand Down Expand Up @@ -496,7 +500,7 @@ void RosExecutor::timer_callback(const ros::TimerEvent& timer_ev)

_model->update();

if(_robot && !_visual_mode)
if(!_pause_command && _robot && !_visual_mode)
{
_robot->setReferenceFrom(*_model, Sync::Position, Sync::Velocity);
_robot->move();
Expand Down Expand Up @@ -575,6 +579,25 @@ bool RosExecutor::reset_joints_callback(cartesian_interface::ResetJointsRequest&
}


bool RosExecutor::pause_cartesio_callback(std_srvs::SetBoolRequest& req,
std_srvs::SetBoolRequest& res)
{
/* If resume --> Update robot pos */
if(_pause_command && !req.data){
reset_model_state();

_current_impl->reset(_time);

XBot::JointNameMap q_map;
_model->getJointPosition(q_map);
_current_impl->setReferencePosture(q_map);
}

_pause_command = req.data;

return true;
}

void RosExecutor::world_frame_to_param()
{
/* Upload floating base pose to parameter server */
Expand Down