41 #include <sensor_msgs/JointState.h> 67 ROS_ERROR_NAMED(
"MoveItFakeControllerManager",
"controller_list should be specified as an array");
85 for (
int i = 0; i < controller_list.
size(); ++i)
87 if (!controller_list[i].hasMember(
"name") || !controller_list[i].
hasMember(
"joints"))
89 ROS_ERROR_NAMED(
"MoveItFakeControllerManager",
"Name and joints must be specified for each controller");
95 std::string name = std::string(controller_list[i][
"name"]);
100 << name <<
" is not specified as an array");
103 std::vector<std::string> joints;
104 for (
int j = 0; j < controller_list[i][
"joints"].
size(); ++j)
105 joints.push_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")
120 ROS_ERROR_NAMED(
"MoveItFakeControllerManager",
"Caught unknown exception while parsing controller information");
127 sensor_msgs::JointState js;
131 ROS_ERROR_ONCE_NAMED(
"loadInitialJointValues",
"Parameter 'initial' should be an array of (group, pose) " 137 robot_model::RobotModelPtr robot_model = robot_model_loader.
getModel();
138 typedef std::map<std::string, double> JointPoseMap;
141 for (
int i = 0, end = param.
size(); i != end; ++i)
145 std::string group_name = std::string(param[i][
"group"]);
146 std::string pose_name = std::string(param[i][
"pose"]);
147 if (!robot_model->hasJointModelGroup(group_name))
158 ROS_WARN_NAMED(
"loadInitialJointValues",
"Unknown pose '%s' for group '%s'.", pose_name.c_str(),
162 ROS_INFO_NAMED(
"loadInitialJointValues",
"Set joints of group '%s' to pose '%s'.", group_name.c_str(),
165 for (std::vector<std::string>::const_iterator jit = joint_names.begin(), end = joint_names.end(); jit != end;
185 ROS_ERROR_ONCE_NAMED(
"loadInitialJointValues",
"Caught unknown exception while reading initial pose " 191 for (JointPoseMap::const_iterator it = joints.begin(), end = joints.end(); it != end; ++it)
193 js.name.push_back(it->first);
194 js.position.push_back(it->second);
208 std::map<std::string, BaseFakeControllerPtr>::const_iterator it =
controllers_.find(name);
213 return moveit_controller_manager::MoveItControllerHandlePtr();
221 for (std::map<std::string, BaseFakeControllerPtr>::const_iterator it =
controllers_.begin();
223 names.push_back(it->first);
224 ROS_INFO_STREAM(
"Returned " << names.size() <<
" controllers in list");
248 std::map<std::string, BaseFakeControllerPtr>::const_iterator it =
controllers_.find(name);
251 it->second->getJoints(joints);
255 ROS_WARN(
"The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on " 275 virtual bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
std::size_t getVariableCount() const
#define ROS_INFO_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
sensor_msgs::JointState loadInitialJointValues(XmlRpc::XmlRpcValue ¶m) const
ros::NodeHandle node_handle_
virtual void getLoadedControllers(std::vector< std::string > &names)
static const std::string ROBOT_DESCRIPTION
#define ROS_ERROR_ONCE_NAMED(name,...)
MoveItFakeControllerManager()
Type const & getType() const
virtual void getActiveControllers(std::vector< std::string > &names)
void setToDefaultValues()
virtual ~MoveItFakeControllerManager()
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
#define ROS_FATAL_STREAM(args)
const std::vector< std::string > & getActiveJointModelNames() const
virtual void getControllersList(std::vector< std::string > &names)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
std::map< std::string, BaseFakeControllerPtr > controllers_
const JointModel * getJointModel(const std::string &joint) const
bool hasMember(const std::string &name) const
#define ROS_INFO_STREAM(args)
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_ERROR_NAMED(name,...)
static const std::string DEFAULT_TYPE
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
const robot_model::RobotModelPtr & getModel() const
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
const double * getJointPositions(const std::string &joint_name) const
#define ROS_WARN_STREAM_NAMED(name, args)