moveit_fake_controller_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Ioan A. Sucan nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Dave Coleman, Robert Haschke */
36 
38 #include <ros/ros.h>
41 #include <sensor_msgs/JointState.h>
43 #include <ros/console.h>
44 #include <map>
45 #include <iterator>
46 
48 {
49 static const std::string DEFAULT_TYPE = "interpolate";
50 static const std::string ROBOT_DESCRIPTION = "robot_description";
51 
53 {
54 public:
56  {
57  if (!node_handle_.hasParam("controller_list"))
58  {
59  ROS_ERROR_STREAM_NAMED("MoveItFakeControllerManager", "No controller_list specified.");
60  return;
61  }
62 
63  XmlRpc::XmlRpcValue controller_list;
64  node_handle_.getParam("controller_list", controller_list);
65  if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
66  {
67  ROS_ERROR_NAMED("MoveItFakeControllerManager", "controller_list should be specified as an array");
68  return;
69  }
70 
71  /* by setting latch to true we preserve the initial joint state while other nodes launch */
72  bool latch = true;
73  pub_ = node_handle_.advertise<sensor_msgs::JointState>("fake_controller_joint_states", 100, latch);
74 
75  /* publish initial pose */
76  XmlRpc::XmlRpcValue initial;
77  if (node_handle_.getParam("initial", initial))
78  {
79  sensor_msgs::JointState js = loadInitialJointValues(initial);
80  js.header.stamp = ros::Time::now();
81  pub_.publish(js);
82  }
83 
84  /* actually create each controller */
85  for (int i = 0; i < controller_list.size(); ++i)
86  {
87  if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
88  {
89  ROS_ERROR_NAMED("MoveItFakeControllerManager", "Name and joints must be specified for each controller");
90  continue;
91  }
92 
93  try
94  {
95  std::string name = std::string(controller_list[i]["name"]);
96 
97  if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
98  {
99  ROS_ERROR_STREAM_NAMED("MoveItFakeControllerManager", "The list of joints for controller "
100  << name << " is not specified as an array");
101  continue;
102  }
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]));
106 
107  const std::string& type =
108  controller_list[i].hasMember("type") ? std::string(controller_list[i]["type"]) : DEFAULT_TYPE;
109  if (type == "last point")
110  controllers_[name].reset(new LastPointController(name, joints, pub_));
111  else if (type == "via points")
112  controllers_[name].reset(new ViaPointController(name, joints, pub_));
113  else if (type == "interpolate")
114  controllers_[name].reset(new InterpolatingController(name, joints, pub_));
115  else
116  ROS_ERROR_STREAM("Unknown fake controller type: " << type);
117  }
118  catch (...)
119  {
120  ROS_ERROR_NAMED("MoveItFakeControllerManager", "Caught unknown exception while parsing controller information");
121  }
122  }
123  }
124 
125  sensor_msgs::JointState loadInitialJointValues(XmlRpc::XmlRpcValue& param) const
126  {
127  sensor_msgs::JointState js;
128 
129  if (param.getType() != XmlRpc::XmlRpcValue::TypeArray || param.size() == 0)
130  {
131  ROS_ERROR_ONCE_NAMED("loadInitialJointValues", "Parameter 'initial' should be an array of (group, pose) "
132  "structs.");
133  return js;
134  }
135 
137  robot_model::RobotModelPtr robot_model = robot_model_loader.getModel();
138  typedef std::map<std::string, double> JointPoseMap;
139  JointPoseMap joints;
140 
141  for (int i = 0, end = param.size(); i != end; ++i)
142  {
143  try
144  {
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))
148  {
149  ROS_WARN_STREAM_NAMED("loadInitialJointValues", "Unknown joint model group: " << group_name);
150  continue;
151  }
152  moveit::core::JointModelGroup* jmg = robot_model->getJointModelGroup(group_name);
153  moveit::core::RobotState robot_state(robot_model);
154  const std::vector<std::string>& joint_names = jmg->getActiveJointModelNames();
155 
156  if (!robot_state.setToDefaultValues(jmg, pose_name))
157  {
158  ROS_WARN_NAMED("loadInitialJointValues", "Unknown pose '%s' for group '%s'.", pose_name.c_str(),
159  group_name.c_str());
160  continue;
161  }
162  ROS_INFO_NAMED("loadInitialJointValues", "Set joints of group '%s' to pose '%s'.", group_name.c_str(),
163  pose_name.c_str());
164 
165  for (std::vector<std::string>::const_iterator jit = joint_names.begin(), end = joint_names.end(); jit != end;
166  ++jit)
167  {
168  const moveit::core::JointModel* jm = robot_state.getJointModel(*jit);
169  if (!jm)
170  {
171  ROS_WARN_STREAM_NAMED("loadInitialJointValues", "Unknown joint: " << *jit);
172  continue;
173  }
174  if (jm->getVariableCount() != 1)
175  {
176  ROS_WARN_STREAM_NAMED("loadInitialJointValues", "Cannot handle multi-variable joint: " << *jit);
177  continue;
178  }
179 
180  joints[*jit] = robot_state.getJointPositions(jm)[0];
181  }
182  }
183  catch (...)
184  {
185  ROS_ERROR_ONCE_NAMED("loadInitialJointValues", "Caught unknown exception while reading initial pose "
186  "information.");
187  }
188  }
189 
190  // fill the joint state
191  for (JointPoseMap::const_iterator it = joints.begin(), end = joints.end(); it != end; ++it)
192  {
193  js.name.push_back(it->first);
194  js.position.push_back(it->second);
195  }
196  return js;
197  }
198 
200  {
201  }
202 
203  /*
204  * Get a controller, by controller name (which was specified in the controllers.yaml
205  */
206  virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
207  {
208  std::map<std::string, BaseFakeControllerPtr>::const_iterator it = controllers_.find(name);
209  if (it != controllers_.end())
210  return it->second;
211  else
212  ROS_FATAL_STREAM("No such controller: " << name);
213  return moveit_controller_manager::MoveItControllerHandlePtr();
214  }
215 
216  /*
217  * Get the list of controller names.
218  */
219  virtual void getControllersList(std::vector<std::string>& names)
220  {
221  for (std::map<std::string, BaseFakeControllerPtr>::const_iterator it = controllers_.begin();
222  it != controllers_.end(); ++it)
223  names.push_back(it->first);
224  ROS_INFO_STREAM("Returned " << names.size() << " controllers in list");
225  }
226 
227  /*
228  * Fake controllers are always active
229  */
230  virtual void getActiveControllers(std::vector<std::string>& names)
231  {
232  getControllersList(names);
233  }
234 
235  /*
236  * Fake controllers are always loaded
237  */
238  virtual void getLoadedControllers(std::vector<std::string>& names)
239  {
240  getControllersList(names);
241  }
242 
243  /*
244  * Get the list of joints that a controller can control.
245  */
246  virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
247  {
248  std::map<std::string, BaseFakeControllerPtr>::const_iterator it = controllers_.find(name);
249  if (it != controllers_.end())
250  {
251  it->second->getJoints(joints);
252  }
253  else
254  {
255  ROS_WARN("The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on "
256  "the param server?",
257  name.c_str());
258  joints.clear();
259  }
260  }
261 
262  /*
263  * Controllers are all active and default.
264  */
266  getControllerState(const std::string& name)
267  {
269  state.active_ = true;
270  state.default_ = true;
271  return state;
272  }
273 
274  /* Cannot switch our controllers */
275  virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
276  {
277  return false;
278  }
279 
280 protected:
283  std::map<std::string, BaseFakeControllerPtr> controllers_;
284 };
285 
286 } // end namespace moveit_fake_controller_manager
287 
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 &param) const
virtual void getLoadedControllers(std::vector< std::string > &names)
int size() const
#define ROS_ERROR_ONCE_NAMED(name,...)
Type const & getType() const
#define ROS_WARN(...)
virtual void getActiveControllers(std::vector< std::string > &names)
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)
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 Time now()
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)


moveit_fake_controller_manager
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:17:49