41 #include <sensor_msgs/JointState.h>
66 ROS_ERROR_NAMED(
"MoveItFakeControllerManager",
"controller_list should be specified as an array");
84 for (
int i = 0; i < controller_list.
size(); ++i)
86 if (!controller_list[i].hasMember(
"name") || !controller_list[i].hasMember(
"joints"))
88 ROS_ERROR_NAMED(
"MoveItFakeControllerManager",
"Name and joints must be specified for each controller");
94 const std::string
name = std::string(controller_list[i][
"name"]);
99 "The list of joints for controller " << name <<
" is not specified as an array");
102 std::vector<std::string> joints;
103 joints.reserve(controller_list[i][
"joints"].size());
104 for (
int j = 0; j < controller_list[i][
"joints"].
size(); ++j)
105 joints.emplace_back(std::string(controller_list[i][
"joints"][j]));
107 const std::string& type =
109 if (type ==
"last point")
111 else if (type ==
"via points")
113 else if (type ==
"interpolate")
119 state.
default_ = controller_list[i].
hasMember(
"default") ? (bool)controller_list[i][
"default"] :
false;
126 ROS_ERROR_NAMED(
"MoveItFakeControllerManager",
"Caught unknown exception while parsing controller information");
133 sensor_msgs::JointState js;
137 ROS_ERROR_ONCE_NAMED(
"loadInitialJointValues",
"Parameter 'initial' should be an array of (group, pose) "
145 typedef std::map<std::string, double> JointPoseMap;
148 robot_state.setToDefaultValues();
149 for (
int i = 0, end =
param.size(); i != end; ++i)
153 std::string group_name = std::string(param[i][
"group"]);
154 std::string pose_name = std::string(param[i][
"pose"]);
155 if (!robot_model->hasJointModelGroup(group_name))
163 if (!robot_state.setToDefaultValues(jmg, pose_name))
165 ROS_WARN_NAMED(
"loadInitialJointValues",
"Unknown pose '%s' for group '%s'.", pose_name.c_str(),
169 ROS_INFO_NAMED(
"loadInitialJointValues",
"Set joints of group '%s' to pose '%s'.", group_name.c_str(),
172 for (
const std::string& joint_name : joint_names)
182 ROS_WARN_STREAM_NAMED(
"loadInitialJointValues",
"Cannot handle multi-variable joint: " << joint_name);
186 joints[joint_name] = robot_state.getJointPositions(jm)[0];
191 ROS_ERROR_ONCE_NAMED(
"loadInitialJointValues",
"Caught unknown exception while reading initial pose "
197 for (
const auto& name_pos_pair : joints)
199 js.name.push_back(name_pos_pair.first);
200 js.position.push_back(name_pos_pair.second);
210 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
212 std::map<std::string, BaseFakeControllerPtr>::const_iterator it =
controllers_.find(name);
217 return moveit_controller_manager::MoveItControllerHandlePtr();
225 for (std::map<std::string, BaseFakeControllerPtr>::const_iterator it =
controllers_.begin();
227 names.push_back(it->first);
228 ROS_INFO_STREAM(
"Returned " << names.size() <<
" controllers in list");
250 void getControllerJoints(
const std::string& name, std::vector<std::string>& joints)
override
252 std::map<std::string, BaseFakeControllerPtr>::const_iterator it =
controllers_.find(name);
255 it->second->getJoints(joints);
259 ROS_WARN(
"The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on "
274 const std::vector<std::string>& )
override
283 std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState>
controller_states_;