39 #include <control_msgs/FollowJointTrajectoryAction.h> 43 #include <pr2_mechanism_msgs/ListControllers.h> 44 #include <pr2_mechanism_msgs/SwitchController.h> 45 #include <pr2_mechanism_msgs/LoadController.h> 46 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h> 81 unsigned int attempts = 0;
162 if (!trajectory.multi_dof_joint_trajectory.points.empty())
164 ROS_ERROR(
"The PR2 gripper controller cannot execute multi-dof trajectories.");
168 if (trajectory.joint_trajectory.points.back().positions.empty())
170 ROS_ERROR(
"The PR2 gripper controller expects a joint trajectory with one point that specifies at least one position, but 0 positions provided)");
174 if (trajectory.joint_trajectory.points.size() > 1)
175 ROS_DEBUG(
"The PR2 gripper controller expects a joint trajectory with one point only, but %u provided. Using last point only.", (
unsigned int)trajectory.joint_trajectory.points.size());
177 int gripper_joint_index = -1;
178 for (std::size_t i = 0 ; i < trajectory.joint_trajectory.joint_names.size() ; ++i)
179 if (trajectory.joint_trajectory.joint_names[i] == R_GRIPPER_JOINT || trajectory.joint_trajectory.joint_names[i] == L_GRIPPER_JOINT)
181 gripper_joint_index = i;
185 if (!trajectory.joint_trajectory.joint_names.empty())
187 std::stringstream ss;
189 for (std::size_t i = 0 ; i < trajectory.joint_trajectory.joint_names.size() ; ++i)
190 ss <<
"PR2 gripper trajectory (" << i <<
"): " << trajectory.joint_trajectory.joint_names[i] <<
" " << trajectory.joint_trajectory.points[0].positions[i] << std::endl;
195 if (gripper_joint_index == -1)
197 ROS_ERROR(
"Could not find value for gripper virtual joint. Expected joint value for '%s' or '%s'.", L_GRIPPER_JOINT.c_str(), R_GRIPPER_JOINT.c_str());
201 double gap_opening = trajectory.joint_trajectory.points.back().positions[gripper_joint_index] *
GAP_CONVERSION_RATIO;
202 ROS_DEBUG(
"PR2 gripper gap opening: %f", gap_opening);
205 if (gap_opening > GRIPPER_OPEN)
211 if (gap_opening <= 0.0)
217 pr2_controllers_msgs::Pr2GripperCommandGoal goal;
220 goal.command.position = gap_opening;
233 const pr2_controllers_msgs::Pr2GripperCommandResultConstPtr& result)
267 if (!trajectory.multi_dof_joint_trajectory.points.empty())
269 ROS_ERROR(
"The PR2 FollowJointTrajectory controller cannot execute multi-dof trajectories.");
275 ROS_DEBUG_STREAM(
"Sending continuation for the currently executed trajectory to FollowJointTrajectory action for controller " <<
name_);
276 control_msgs::FollowJointTrajectoryGoal goal;
277 goal.trajectory = trajectory.joint_trajectory;
290 const control_msgs::FollowJointTrajectoryResultConstPtr& result)
311 if (node_handle_.hasParam(
"controller_manager_name"))
312 node_handle_.getParam(
"controller_manager_name", controller_manager_name_);
313 if (controller_manager_name_.empty())
314 node_handle_.param(
"pr2_controller_manager_name", controller_manager_name_, std::string(
"pr2_controller_manager"));
315 if (node_handle_.hasParam(
"use_controller_manager"))
316 node_handle_.param(
"use_controller_manager", use_controller_manager_,
true);
318 node_handle_.param(
"use_pr2_controller_manager", use_controller_manager_,
true);
321 if (node_handle_.hasParam(
"controller_list"))
323 node_handle_.getParam(
"controller_list", controller_list);
325 ROS_WARN(
"Controller list should be specified as an array");
327 for (
int i = 0 ; i < controller_list.
size() ; ++i)
328 if (!controller_list[i].hasMember(
"name") || !controller_list[i].
hasMember(
"joints"))
329 ROS_WARN(
"Name and joints must be specifed for each controller");
335 std::string name = std::string(controller_list[i][
"name"]);
336 if (controller_list[i].hasMember(
"default"))
342 ci.
default_ = controller_list[i][
"default"];
346 std::string def = std::string(controller_list[i][
"default"]);
347 std::transform(def.begin(), def.end(), def.begin(), ::tolower);
348 if (def ==
"true" || def ==
"yes")
357 if (controller_list[i].hasMember(
"ns"))
359 ci.
ns_ = std::string(controller_list[i][
"ns"]);
360 ROS_WARN(
"'ns' argument specified. Please use 'action_ns' instead.");
362 if (controller_list[i].hasMember(
"action_ns"))
363 ci.
ns_ = std::string(controller_list[i][
"action_ns"]);
366 int nj = controller_list[i][
"joints"].
size();
367 for (
int j = 0 ; j < nj ; ++j)
368 ci.
joints_.push_back(std::string(controller_list[i][
"joints"][j]));
371 ROS_WARN_STREAM(
"The list of joints for controller " << name <<
" is not specified as an array");
373 possibly_unloaded_controllers_[name] = ci;
377 ROS_ERROR(
"Unable to parse controller information");
383 if (use_controller_manager_)
384 ROS_DEBUG_STREAM(
"No controller list specified. Using list obtained from the " << controller_manager_name_);
386 ROS_ERROR_STREAM(
"Not using a controller manager and no controllers specified. There are no known controllers.");
389 if (use_controller_manager_)
391 static const unsigned int max_attempts = 5;
392 unsigned int attempts = 0;
394 ROS_INFO_STREAM(
"Waiting for service " << controller_manager_name_ +
"/list_controllers" <<
" to come up");
396 if (attempts < max_attempts)
398 ROS_INFO_STREAM(
"Waiting for service " << controller_manager_name_ +
"/switch_controller" <<
" to come up");
400 if (attempts < max_attempts)
402 ROS_INFO_STREAM(
"Waiting for service " << controller_manager_name_ +
"/load_controller" <<
" to come up");
404 if (attempts < max_attempts)
406 lister_service_ = root_node_handle_.serviceClient<pr2_mechanism_msgs::ListControllers>(controller_manager_name_ +
"/list_controllers",
true);
407 switcher_service_ = root_node_handle_.serviceClient<pr2_mechanism_msgs::SwitchController>(controller_manager_name_ +
"/switch_controller",
true);
408 loader_service_ = root_node_handle_.serviceClient<pr2_mechanism_msgs::LoadController>(controller_manager_name_ +
"/load_controller",
true);
411 ROS_ERROR(
"Not using the PR2 controller manager");
421 std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>::const_iterator it = handle_cache_.find(name);
422 if (it != handle_cache_.end())
425 moveit_controller_manager::MoveItControllerHandlePtr new_handle;
426 if (possibly_unloaded_controllers_.find(name) != possibly_unloaded_controllers_.end())
428 const std::string &ns = possibly_unloaded_controllers_.at(name).ns_;
429 new_handle = getControllerHandleHelper(name, ns);
432 new_handle = getControllerHandleHelper(name,
"");
435 handle_cache_[name] = new_handle;
441 const pr2_mechanism_msgs::ListControllers::Response &res = getListControllerServiceResponse();
442 std::set<std::string> names_set;
443 names_set.insert(res.controllers.begin(), res.controllers.end());
445 for (std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.begin() ; it != possibly_unloaded_controllers_.end() ; ++it)
446 names_set.insert(it->first);
449 names.insert(names.end(), names_set.begin(), names_set.end());
455 if (use_controller_manager_)
457 const pr2_mechanism_msgs::ListControllers::Response &res = getListControllerServiceResponse();
458 for (std::size_t i = 0; i < res.controllers.size(); ++i)
459 if (res.state[i] ==
"running")
460 names.push_back(res.controllers[i]);
464 for (std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.begin() ; it != possibly_unloaded_controllers_.end() ; ++it)
465 names.push_back(it->first);
470 std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.find(name);
471 if (it != possibly_unloaded_controllers_.end())
472 joints = it->second.joints_;
476 std::string param_name;
477 if (node_handle_.searchParam(name +
"/joints", param_name))
480 node_handle_.getParam(param_name, joints_list);
482 for (
int i = 0 ; i < joints_list.
size() ; ++i)
483 joints.push_back((std::string)joints_list[i]);
486 if (node_handle_.searchParam(name +
"/joint", param_name))
488 std::string joint_name;
489 if (node_handle_.getParam(param_name, joint_name))
490 joints.push_back(joint_name);
493 ROS_INFO(
"The joints for controller '%s' are not known and were not found on the ROS param server under '%s/joints'or '%s/joint'. " 494 "Perhaps the controller configuration is not loaded on the param server?", name.c_str(), name.c_str(), name.c_str());
503 if (use_controller_manager_)
505 const pr2_mechanism_msgs::ListControllers::Response &res = getListControllerServiceResponse();
506 for (std::size_t i = 0; i < res.controllers.size(); ++i)
508 if (res.controllers[i] == name)
510 if (res.state[i] ==
"running")
522 std::map<std::string, ControllerInformation>::const_iterator it = possibly_unloaded_controllers_.find(name);
523 if (it != possibly_unloaded_controllers_.end())
524 if (it->second.default_)
529 virtual bool switchControllers(
const std::vector<std::string> &activate,
const std::vector<std::string> &deactivate)
531 if (!use_controller_manager_)
533 ROS_WARN_STREAM(
"Cannot switch controllers without using the controller manager");
537 if (!activate.empty())
540 const std::vector<std::string> &loaded_c = getListControllerServiceResponse().controllers;
541 std::set<std::string> loaded_c_set(loaded_c.begin(), loaded_c.end());
542 for (std::size_t i = 0 ; i < activate.size() ; ++i)
543 if (loaded_c_set.find(activate[i]) == loaded_c_set.end())
545 handle_cache_.erase(activate[i]);
546 pr2_mechanism_msgs::LoadController::Request req;
547 pr2_mechanism_msgs::LoadController::Response res;
548 req.name = activate[i];
549 if (!loader_service_.call(req, res))
551 ROS_WARN(
"Something went wrong with loader service while trying to load '%s'", req.name.c_str());
556 ROS_WARN(
"Loading controller '%s' failed", req.name.c_str());
563 pr2_mechanism_msgs::SwitchController::Request req;
564 pr2_mechanism_msgs::SwitchController::Response res;
566 req.strictness = pr2_mechanism_msgs::SwitchController::Request::BEST_EFFORT;
567 req.start_controllers = activate;
568 req.stop_controllers = deactivate;
569 if (!switcher_service_.call(req, res))
583 if (use_controller_manager_)
588 pr2_mechanism_msgs::ListControllers::Request req;
589 if (!lister_service_.call(req, cached_lister_response_))
594 return cached_lister_response_;
599 moveit_controller_manager::MoveItControllerHandlePtr new_handle;
600 if (name ==
"l_gripper_controller" || name ==
"r_gripper_controller")
603 if (!static_cast<Pr2GripperControllerHandle*>(new_handle.get())->
isConnected())
609 if (!static_cast<Pr2FollowJointTrajectoryControllerHandle*>(new_handle.get())->
isConnected())
627 std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>
handle_cache_;
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > handle_cache_
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
const pr2_mechanism_msgs::ListControllers::Response & getListControllerServiceResponse()
moveit_controller_manager::ExecutionStatus last_exec_
static const double DEFAULT_MAX_GRIPPER_EFFORT
Maximum effort the PR2 gripper is allowed to exert (read as 'very large value'); this is PR2 specific...
static const double GRIPPER_CLOSED
The distance between the PR2 gripper fingers when fully closed (in m); this is PR2 specific...
pr2_mechanism_msgs::ListControllers::Response cached_lister_response_
ros::ServiceClient switcher_service_
virtual void getControllersList(std::vector< std::string > &names)
Pr2FollowJointTrajectoryControllerHandle(const std::string &name, const std::string &ns="follow_joint_trajectory")
Type const & getType() const
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
static const std::string R_GRIPPER_JOINT
The name of the joint we expect input for to decide how to actuate the right gripper; this is PR2 spe...
ActionBasedControllerHandle(const std::string &name, const std::string &ns)
static const std::string L_GRIPPER_JOINT
The name of the joint we expect input for to decide how to actuate the left gripper; this is PR2 spec...
Pr2GripperControllerHandle(const std::string &name, const std::string &ns="gripper_action")
void controllerFeedbackCallback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
ros::NodeHandle node_handle_
std::string toString() const
std::string controller_manager_name_
boost::shared_ptr< actionlib::SimpleActionClient< T > > controller_action_client_
void controllerActiveCallback()
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandleHelper(const std::string &name, const std::string &ns)
virtual ~Pr2MoveItControllerManager()
virtual bool cancelExecution()
ros::Time last_lister_response_
static const double GAP_CONVERSION_RATIO
The conversion ratio that needs to be applied to get the gap opening of the gripper (m) based on the ...
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
std::string getText() const
ros::ServiceClient loader_service_
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ros::NodeHandle root_node_handle_
MoveItControllerHandle(const std::string &name)
static const double GRIPPER_OPEN
The distance between the PR2 gripper fingers when fully open (in m); this is PR2 specific.
bool hasMember(const std::string &name) const
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
void controllerActiveCallback()
PLUGINLIB_EXPORT_CLASS(pr2_moveit_controller_manager::Pr2MoveItControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_INFO_STREAM(args)
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const pr2_controllers_msgs::Pr2GripperCommandResultConstPtr &result)
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
Pr2MoveItControllerManager()
ros::ServiceClient lister_service_
#define ROS_ERROR_STREAM(args)
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
void controllerFeedbackCallback(const pr2_controllers_msgs::Pr2GripperCommandFeedbackConstPtr &feedback)
virtual bool waitForExecution(const ros::Duration &timeout=ros::Duration(0))
bool use_controller_manager_
std::map< std::string, ControllerInformation > possibly_unloaded_controllers_
virtual void getActiveControllers(std::vector< std::string > &names)
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)