39 #include <moveit_ros_planning/TrajectoryExecutionDynamicReconfigureConfig.h> 
   41 #include <dynamic_reconfigure/server.h> 
   45 static const std::string 
LOGNAME = 
"trajectory_execution_manager";
 
   58 using namespace moveit_ros_planning;
 
   64     : owner_(owner), dynamic_reconfigure_server_(
ros::NodeHandle(
"~/trajectory_execution"))
 
   66     dynamic_reconfigure_server_.setCallback(
 
   67         [
this](
const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
 
   73     owner_->enableExecutionDurationMonitoring(config.execution_duration_monitoring);
 
   74     owner_->setAllowedExecutionDurationScaling(config.allowed_execution_duration_scaling);
 
   75     owner_->setAllowedGoalDurationMargin(config.allowed_goal_duration_margin);
 
   76     owner_->setExecutionVelocityScaling(config.execution_velocity_scaling);
 
   77     owner_->setAllowedStartTolerance(config.allowed_start_tolerance);
 
   78     owner_->setWaitForTrajectoryCompletion(config.wait_for_trajectory_completion);
 
   86                                                        const planning_scene_monitor::CurrentStateMonitorPtr& csm)
 
   87   : robot_model_(robot_model), csm_(csm), node_handle_(
"~")
 
   96                                                        const planning_scene_monitor::CurrentStateMonitorPtr& csm,
 
   97                                                        bool manage_controllers)
 
   98   : robot_model_(robot_model), csm_(csm), node_handle_(
"~"), manage_controllers_(manage_controllers)
 
  131         std::make_unique<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager>>(
 
  132             "moveit_core", 
"moveit_controller_manager::MoveItControllerManager");
 
  142     std::string controller;
 
  146       if (classes.size() == 1)
 
  148         controller = classes[0];
 
  150                        "Parameter '~moveit_controller_manager' is not specified but only one " 
  151                        "matching plugin was found: '%s'. Using that one.",
 
  156                                  "identify the plugin to use for interacting with controllers. No paths can " 
  160     if (!controller.empty())
 
  168                                "Exception while loading controller manager '" << controller << 
"': " << ex.what());
 
  244   if (controller.empty())
 
  245     return push(trajectory, std::vector<std::string>());
 
  247     return push(trajectory, std::vector<std::string>(1, controller));
 
  252   if (controller.empty())
 
  253     return push(trajectory, std::vector<std::string>());
 
  255     return push(trajectory, std::vector<std::string>(1, controller));
 
  259                                       const std::vector<std::string>& controllers)
 
  261   moveit_msgs::RobotTrajectory traj;
 
  262   traj.joint_trajectory = trajectory;
 
  263   return push(traj, controllers);
 
  267                                       const std::vector<std::string>& controllers)
 
  276   if (
configure(*context, trajectory, controllers))
 
  280       std::stringstream ss;
 
  281       ss << 
"Pushed trajectory for execution using controllers [ ";
 
  282       for (
const std::string& controller : context->
controllers_)
 
  283         ss << controller << 
" ";
 
  284       ss << 
"]:" << std::endl;
 
  285       for (
const moveit_msgs::RobotTrajectory& trajectory_part : context->
trajectory_parts_)
 
  286         ss << trajectory_part << std::endl;
 
  306     std::vector<std::string> names;
 
  308     for (
const std::string& 
name : names)
 
  310       std::vector<std::string> joints;
 
  314       ci.
joints_.insert(joints.begin(), joints.end());
 
  318     for (std::map<std::string, ControllerInformation>::iterator it = 
known_controllers_.begin();
 
  320       for (std::map<std::string, ControllerInformation>::iterator jt = 
known_controllers_.begin();
 
  324           std::vector<std::string> intersect;
 
  325           std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), jt->second.joints_.begin(),
 
  326                                 jt->second.joints_.end(), std::back_inserter(intersect));
 
  327           if (!intersect.empty())
 
  329             it->second.overlapping_controllers_.insert(jt->first);
 
  330             jt->second.overlapping_controllers_.insert(it->first);
 
  338   std::map<std::string, ControllerInformation>::iterator it = 
known_controllers_.find(controller);
 
  363   for (std::pair<const std::string, ControllerInformation>& known_controller : 
known_controllers_)
 
  368                                                             const std::set<std::string>& actuated_joints)
 
  370   std::set<std::string> combined_joints;
 
  371   for (
const std::string& controller : selected)
 
  379     std::stringstream ss, saj, sac;
 
  380     for (
const std::string& controller : selected)
 
  381       ss << controller << 
" ";
 
  382     for (
const std::string& actuated_joint : actuated_joints)
 
  383       saj << actuated_joint << 
" ";
 
  384     for (
const std::string& combined_joint : combined_joints)
 
  385       sac << combined_joint << 
" ";
 
  386     ROS_INFO_NAMED(
LOGNAME, 
"Checking if controllers [ %s] operating on joints [ %s] cover joints [ %s]",
 
  387                    ss.str().c_str(), sac.str().c_str(), saj.str().c_str());
 
  390   return std::includes(combined_joints.begin(), combined_joints.end(), actuated_joints.begin(), actuated_joints.end());
 
  394                                                                const std::vector<std::string>& available_controllers,
 
  395                                                                std::vector<std::string>& selected_controllers,
 
  397                                                                const std::set<std::string>& actuated_joints)
 
  399   if (selected_controllers.size() == controller_count)
 
  406   for (std::size_t i = start_index; i < available_controllers.size(); ++i)
 
  410     for (std::size_t j = 0; j < selected_controllers.size() && !
overlap; ++j)
 
  417     selected_controllers.push_back(available_controllers[i]);
 
  420     selected_controllers.pop_back();
 
  426 struct OrderPotentialControllerCombination
 
  428   bool operator()(
const std::size_t a, 
const std::size_t b)
 const 
  459                                                  std::size_t controller_count,
 
  460                                                  const std::vector<std::string>& available_controllers,
 
  461                                                  std::vector<std::string>& selected_controllers)
 
  464   std::vector<std::string> work_area;
 
  465   OrderPotentialControllerCombination order;
 
  466   std::vector<std::vector<std::string>>& 
selected_options = order.selected_options;
 
  472     std::stringstream saj;
 
  473     std::stringstream sac;
 
  474     for (
const std::string& available_controller : available_controllers)
 
  475       sac << available_controller << 
" ";
 
  476     for (
const std::string& actuated_joint : actuated_joints)
 
  477       saj << actuated_joint << 
" ";
 
  478     ROS_INFO_NAMED(
LOGNAME, 
"Looking for %zu controllers among [ %s] that cover joints [ %s]. Found %zd options.",
 
  479                    controller_count, sac.str().c_str(), saj.str().c_str(), 
selected_options.size());
 
  509         order.nrdefault[i]++;
 
  512       order.nrjoints[i] += ci.
joints_.size();
 
  522   std::sort(bijection.begin(), bijection.end(), order);
 
  549   for (
const std::string& controller : controllers)
 
  552     std::map<std::string, ControllerInformation>::iterator it = 
known_controllers_.find(controller);
 
  560                                                    const std::vector<std::string>& available_controllers,
 
  561                                                    std::vector<std::string>& selected_controllers)
 
  563   for (std::size_t i = 1; i <= available_controllers.size(); ++i)
 
  564     if (
findControllers(actuated_joints, i, available_controllers, selected_controllers))
 
  569         std::vector<std::string> other_option;
 
  570         for (std::size_t j = i + 1; j <= available_controllers.size(); ++j)
 
  571           if (
findControllers(actuated_joints, j, available_controllers, other_option))
 
  575               selected_controllers = other_option;
 
  586                                                       const std::vector<std::string>& controllers,
 
  587                                                       std::vector<moveit_msgs::RobotTrajectory>& parts)
 
  590   parts.resize(controllers.size());
 
  592   std::set<std::string> actuated_joints_mdof;
 
  593   actuated_joints_mdof.insert(trajectory.multi_dof_joint_trajectory.joint_names.begin(),
 
  594                               trajectory.multi_dof_joint_trajectory.joint_names.end());
 
  595   std::set<std::string> actuated_joints_single;
 
  596   for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
 
  603       actuated_joints_single.insert(jm->
getName());
 
  607   for (std::size_t i = 0; i < controllers.size(); ++i)
 
  609     std::map<std::string, ControllerInformation>::iterator it = 
known_controllers_.find(controllers[i]);
 
  615     std::vector<std::string> intersect_mdof;
 
  616     std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_mdof.begin(),
 
  617                           actuated_joints_mdof.end(), std::back_inserter(intersect_mdof));
 
  618     std::vector<std::string> intersect_single;
 
  619     std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_single.begin(),
 
  620                           actuated_joints_single.end(), std::back_inserter(intersect_single));
 
  621     if (intersect_mdof.empty() && intersect_single.empty())
 
  624       if (!intersect_mdof.empty())
 
  626         std::vector<std::string>& jnames = parts[i].multi_dof_joint_trajectory.joint_names;
 
  627         jnames.insert(jnames.end(), intersect_mdof.begin(), intersect_mdof.end());
 
  628         std::map<std::string, std::size_t> 
index;
 
  629         for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
 
  630           index[trajectory.multi_dof_joint_trajectory.joint_names[j]] = j;
 
  631         std::vector<std::size_t> bijection(jnames.size());
 
  632         for (std::size_t j = 0; j < jnames.size(); ++j)
 
  633           bijection[j] = 
index[jnames[j]];
 
  635         parts[i].multi_dof_joint_trajectory.points.resize(trajectory.multi_dof_joint_trajectory.points.size());
 
  636         for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.points.size(); ++j)
 
  638           parts[i].multi_dof_joint_trajectory.points[j].time_from_start =
 
  639               trajectory.multi_dof_joint_trajectory.points[j].time_from_start;
 
  640           parts[i].multi_dof_joint_trajectory.points[j].transforms.resize(bijection.size());
 
  641           for (std::size_t k = 0; k < bijection.size(); ++k)
 
  643             parts[i].multi_dof_joint_trajectory.points[j].transforms[k] =
 
  644                 trajectory.multi_dof_joint_trajectory.points[j].transforms[bijection[k]];
 
  646             if (!trajectory.multi_dof_joint_trajectory.points[j].velocities.empty())
 
  648               parts[i].multi_dof_joint_trajectory.points[j].velocities.resize(bijection.size());
 
  650               parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.x =
 
  653               parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.y =
 
  656               parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.z =
 
  659               parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.x =
 
  662               parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.y =
 
  665               parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.z =
 
  671       if (!intersect_single.empty())
 
  673         std::vector<std::string>& jnames = parts[i].joint_trajectory.joint_names;
 
  674         jnames.insert(jnames.end(), intersect_single.begin(), intersect_single.end());
 
  675         parts[i].joint_trajectory.header = trajectory.joint_trajectory.header;
 
  676         std::map<std::string, std::size_t> 
index;
 
  677         for (std::size_t j = 0; j < trajectory.joint_trajectory.joint_names.size(); ++j)
 
  678           index[trajectory.joint_trajectory.joint_names[j]] = j;
 
  679         std::vector<std::size_t> bijection(jnames.size());
 
  680         for (std::size_t j = 0; j < jnames.size(); ++j)
 
  681           bijection[j] = 
index[jnames[j]];
 
  682         parts[i].joint_trajectory.points.resize(trajectory.joint_trajectory.points.size());
 
  683         for (std::size_t j = 0; j < trajectory.joint_trajectory.points.size(); ++j)
 
  685           parts[i].joint_trajectory.points[j].time_from_start = trajectory.joint_trajectory.points[j].time_from_start;
 
  686           if (!trajectory.joint_trajectory.points[j].positions.empty())
 
  688             parts[i].joint_trajectory.points[j].positions.resize(bijection.size());
 
  689             for (std::size_t k = 0; k < bijection.size(); ++k)
 
  690               parts[i].joint_trajectory.points[j].positions[k] =
 
  691                   trajectory.joint_trajectory.points[j].positions[bijection[k]];
 
  693           if (!trajectory.joint_trajectory.points[j].velocities.empty())
 
  695             parts[i].joint_trajectory.points[j].velocities.resize(bijection.size());
 
  696             for (std::size_t k = 0; k < bijection.size(); ++k)
 
  697               parts[i].joint_trajectory.points[j].velocities[k] =
 
  700           if (!trajectory.joint_trajectory.points[j].accelerations.empty())
 
  702             parts[i].joint_trajectory.points[j].accelerations.resize(bijection.size());
 
  703             for (std::size_t k = 0; k < bijection.size(); ++k)
 
  704               parts[i].joint_trajectory.points[j].accelerations[k] =
 
  705                   trajectory.joint_trajectory.points[j].accelerations[bijection[k]];
 
  707           if (!trajectory.joint_trajectory.points[j].effort.empty())
 
  709             parts[i].joint_trajectory.points[j].effort.resize(bijection.size());
 
  710             for (std::size_t k = 0; k < bijection.size(); ++k)
 
  711               parts[i].joint_trajectory.points[j].effort[k] =
 
  712                   trajectory.joint_trajectory.points[j].effort[bijection[k]];
 
  728   moveit::core::RobotStatePtr current_state;
 
  731     ROS_WARN_NAMED(
LOGNAME, 
"Failed to validate trajectory: couldn't receive full current joint state within 1s");
 
  737     if (!trajectory.joint_trajectory.points.empty())
 
  740       const std::vector<double>& positions = trajectory.joint_trajectory.points.front().positions;
 
  741       const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
 
  742       if (positions.size() != joint_names.size())
 
  749       for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
 
  758         double cur_position = current_state->getJointPositions(jm)[0];
 
  759         double traj_position = positions[i];
 
  764         if (joint_start_tolerance != 0 && jm->
distance(&cur_position, &traj_position) > joint_start_tolerance)
 
  767                           "\nInvalid Trajectory: start point deviates from current robot state more than %g" 
  768                           "\njoint '%s': expected: %g, current: %g",
 
  769                           joint_start_tolerance, joint_names[i].c_str(), traj_position, cur_position);
 
  774     if (!trajectory.multi_dof_joint_trajectory.points.empty())
 
  777       const std::vector<geometry_msgs::Transform>& transforms =
 
  778           trajectory.multi_dof_joint_trajectory.points.front().transforms;
 
  779       const std::vector<std::string>& joint_names = trajectory.multi_dof_joint_trajectory.joint_names;
 
  780       if (transforms.size() != joint_names.size())
 
  787       for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
 
  798         Eigen::Isometry3d cur_transform, start_transform;
 
  803         Eigen::Vector3d offset = cur_transform.translation() - start_transform.translation();
 
  804         Eigen::AngleAxisd rotation;
 
  805         rotation.fromRotationMatrix(cur_transform.linear().transpose() * start_transform.linear());
 
  807         if (joint_start_tolerance != 0 &&
 
  808             ((offset.array() > joint_start_tolerance).any() || rotation.angle() > joint_start_tolerance))
 
  811                                  "\nInvalid Trajectory: start point deviates from current robot state more than " 
  812                                      << joint_start_tolerance << 
"\nmulti-dof joint '" << joint_names[i]
 
  813                                      << 
"': pos delta: " << offset.transpose() << 
" rot delta: " << rotation.angle());
 
  823                                            const moveit_msgs::RobotTrajectory& trajectory,
 
  824                                            const std::vector<std::string>& controllers)
 
  827   if (trajectory.multi_dof_joint_trajectory.points.empty() && trajectory.joint_trajectory.points.empty())
 
  831   if ((trajectory.joint_trajectory.header.stamp + trajectory.joint_trajectory.points.back().time_from_start).isZero())
 
  838   std::set<std::string> actuated_joints;
 
  840   auto is_actuated = [
this](
const std::string& joint_name) -> 
bool {
 
  844   for (
const std::string& joint_name : trajectory.multi_dof_joint_trajectory.joint_names)
 
  845     if (is_actuated(joint_name))
 
  846       actuated_joints.insert(joint_name);
 
  847   for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
 
  848     if (is_actuated(joint_name))
 
  849       actuated_joints.insert(joint_name);
 
  851   if (actuated_joints.empty())
 
  857   if (controllers.empty())
 
  860     bool reloaded = 
false;
 
  864       std::vector<std::string> all_controller_names;
 
  865       for (std::map<std::string, ControllerInformation>::const_iterator it = 
known_controllers_.begin();
 
  867         all_controller_names.push_back(it->first);
 
  889     bool reloaded = 
false;
 
  890     for (
const std::string& controller : controllers)
 
  898       for (
const std::string& controller : controllers)
 
  910   std::stringstream ss;
 
  911   for (
const std::string& actuated_joint : actuated_joints)
 
  912     ss << actuated_joint << 
" ";
 
  913   ROS_ERROR_NAMED(
LOGNAME, 
"Unable to identify any set of controllers that can actuate the specified joints: [ %s]",
 
  916   std::stringstream ss2;
 
  917   std::map<std::string, ControllerInformation>::const_iterator mi;
 
  920     ss2 << 
"controller '" << mi->second.name_ << 
"' controls joints:\n";
 
  922     std::set<std::string>::const_iterator ji;
 
  923     for (ji = mi->second.joints_.begin(); ji != mi->second.joints_.end(); ji++)
 
  925       ss2 << 
"  " << *ji << std::endl;
 
  941   for (moveit_controller_manager::MoveItControllerHandlePtr& active_handle : 
active_handles_)
 
  944       active_handle->cancelExecution();
 
  946     catch (std::exception& ex)
 
 1028                                                       part_callback, auto_clear);
 
 1079     if (epart && part_callback)
 
 1121     std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles;
 
 1131         for (std::size_t i = 0; i < context.
controllers_.size(); ++i)
 
 1133           moveit_controller_manager::MoveItControllerHandlePtr h;
 
 1138           catch (std::exception& ex)
 
 1161           catch (std::exception& ex)
 
 1167             for (std::size_t j = 0; j < i; ++j)
 
 1172               catch (std::exception& ex)
 
 1192     int longest_part = -1;
 
 1201         if (context.
trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp > current_time)
 
 1202           d = std::max(
d, context.
trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp - current_time);
 
 1208                           context.
trajectory_parts_[i].multi_dof_joint_trajectory.points.back().time_from_start);
 
 1210         if (longest_part < 0 ||
 
 1213                 std::max(context.
trajectory_parts_[longest_part].joint_trajectory.points.size(),
 
 1214                          context.
trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()))
 
 1221       std::map<std::string, double>::const_iterator scaling_it =
 
 1224                                          scaling_it->second :
 
 1227       std::map<std::string, double>::const_iterator margin_it =
 
 1234       expected_trajectory_duration =
 
 1235           std::max(
d * current_scaling + 
ros::Duration(current_margin), expected_trajectory_duration);
 
 1239     if (longest_part >= 0)
 
 1244           context.
trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size())
 
 1247         if (context.
trajectory_parts_[longest_part].joint_trajectory.header.stamp > current_time)
 
 1248           d = context.
trajectory_parts_[longest_part].joint_trajectory.header.stamp - current_time;
 
 1249         for (trajectory_msgs::JointTrajectoryPoint& 
point :
 
 1256         if (context.
trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp > current_time)
 
 1257           d = context.
trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp - current_time;
 
 1258         for (trajectory_msgs::MultiDOFJointTrajectoryPoint& 
point :
 
 1265     for (moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
 
 1269         if (!handle->waitForExecution(expected_trajectory_duration))
 
 1273                             "Controller is taking too long to execute trajectory (the expected upper " 
 1274                             "bound for the trajectory execution was %lf seconds). Stopping trajectory.",
 
 1275                             expected_trajectory_duration.
toSec());
 
 1287         handle->waitForExecution();
 
 1298                                                             << handle->getLastExecutionStatus().asString());
 
 1334   double time_remaining = wait_time;
 
 1336   moveit::core::RobotStatePtr prev_state, cur_state;
 
 1337   prev_state = 
csm_->getCurrentState();
 
 1338   prev_state->enforceBounds();
 
 1341   unsigned int no_motion_count = 0;  
 
 1342   while (time_remaining > 0. && no_motion_count < 3)
 
 1344     if (!
csm_->waitForCurrentState(
ros::Time::now(), time_remaining) || !(cur_state = 
csm_->getCurrentState()))
 
 1349     cur_state->enforceBounds();
 
 1356       const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
 
 1357       const std::size_t n = joint_names.size();
 
 1359       for (std::size_t i = 0; i < n && !moved; ++i)
 
 1366         if (fabs(cur_state->getJointPositions(jm)[0] - prev_state->getJointPositions(jm)[0]) > joint_tolerance)
 
 1369           no_motion_count = 0;
 
 1378     std::swap(prev_state, cur_state);
 
 1381   return time_remaining > 0;
 
 1388     return std::make_pair(-1, -1);
 
 1391   std::vector<ros::Time>::const_iterator time_index_it =
 
 1397 const std::vector<TrajectoryExecutionManager::TrajectoryExecutionContext*>&
 
 1411   if (joint_model_group)
 
 1419   std::vector<std::string> all_controller_names;
 
 1420   for (std::map<std::string, ControllerInformation>::const_iterator it = 
known_controllers_.begin();
 
 1422     all_controller_names.push_back(it->first);
 
 1423   std::vector<std::string> selected_controllers;
 
 1424   std::set<std::string> jset;
 
 1425   for (
const std::string& joint : joints)
 
 1453     std::vector<std::string> controllers_to_activate;
 
 1454     std::vector<std::string> controllers_to_deactivate;
 
 1455     std::set<std::string> joints_to_be_activated;
 
 1456     std::set<std::string> joints_to_be_deactivated;
 
 1457     for (
const std::string& controller : controllers)
 
 1459       std::map<std::string, ControllerInformation>::const_iterator it = 
known_controllers_.find(controller);
 
 1465       if (!it->second.state_.active_)
 
 1468         controllers_to_activate.push_back(controller);
 
 1469         joints_to_be_activated.insert(it->second.joints_.begin(), it->second.joints_.end());
 
 1470         for (
const std::string& overlapping_controller : it->second.overlapping_controllers_)
 
 1475             controllers_to_deactivate.push_back(overlapping_controller);
 
 1476             joints_to_be_deactivated.insert(ci.
joints_.begin(), ci.
joints_.end());
 
 1483     std::set<std::string> diff;
 
 1484     std::set_difference(joints_to_be_deactivated.begin(), joints_to_be_deactivated.end(),
 
 1485                         joints_to_be_activated.begin(), joints_to_be_activated.end(), std::inserter(diff, diff.end()));
 
 1489       std::vector<std::string> possible_additional_controllers;
 
 1490       for (std::map<std::string, ControllerInformation>::const_iterator it = 
known_controllers_.begin();
 
 1494         for (
const std::string& controller_to_activate : controllers_to_activate)
 
 1495           if (it->second.overlapping_controllers_.find(controller_to_activate) !=
 
 1496               it->second.overlapping_controllers_.end())
 
 1502           possible_additional_controllers.push_back(it->first);
 
 1506       std::vector<std::string> additional_controllers;
 
 1507       if (
selectControllers(diff, possible_additional_controllers, additional_controllers))
 
 1508         controllers_to_activate.insert(controllers_to_activate.end(), additional_controllers.begin(),
 
 1509                                        additional_controllers.end());
 
 1513     if (!controllers_to_activate.empty() || !controllers_to_deactivate.empty())
 
 1518         for (
const std::string& controller_to_activate : controllers_to_activate)
 
 1524         for (
const std::string& controller_to_activate : controllers_to_deactivate)
 
 1526         return controller_manager_->switchControllers(controllers_to_activate, controllers_to_deactivate);
 
 1536     std::set<std::string> originally_active;
 
 1537     for (std::map<std::string, ControllerInformation>::const_iterator it = 
known_controllers_.begin();
 
 1539       if (it->second.state_.active_)
 
 1540         originally_active.insert(it->first);
 
 1541     return std::includes(originally_active.begin(), originally_active.end(), controllers.begin(), controllers.end());
 
 1551     for (
int i = 0; i < controller_list.
size(); ++i)  
 
 1556         if (controller.
hasMember(
"allowed_execution_duration_scaling"))
 
 1558               controller[
"allowed_execution_duration_scaling"];
 
 1559         if (controller.
hasMember(
"allowed_goal_duration_margin"))
 
 1561               controller[
"allowed_goal_duration_margin"];