moveit2
The MoveIt Motion Planning Framework for ROS 2.
wrap_python_robot_interface.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
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 Willow Garage 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 */
36 
43 #include <moveit_msgs/msg/robot_state.hpp>
44 #include <visualization_msgs/MarkerArray.h>
45 
46 #include <stdexcept>
47 #include <boost/python.hpp>
48 #include <Python.h>
49 
52 namespace bp = boost::python;
54 
55 namespace moveit
56 {
57 class RobotInterfacePython : protected py_bindings_tools::ROScppInitializer
58 {
59 public:
60  RobotInterfacePython(const std::string& robot_description, const std::string& ns = "")
61  : py_bindings_tools::ROScppInitializer()
62  {
63  robot_model_ = planning_interface::getSharedRobotModel(robot_description);
64  if (!robot_model_)
65  throw std::runtime_error("RobotInterfacePython: invalid robot model");
66  current_state_monitor_ =
68  }
69 
70  const char* getRobotName() const
71  {
72  return robot_model_->getName().c_str();
73  }
74 
75  bp::list getActiveJointNames() const
76  {
77  return py_bindings_tools::listFromString(robot_model_->getActiveJointModelNames());
78  }
79 
80  bp::list getGroupActiveJointNames(const std::string& group) const
81  {
82  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
83  if (jmg)
85  else
86  return bp::list();
87  }
88 
89  bp::list getJointNames() const
90  {
91  return py_bindings_tools::listFromString(robot_model_->getJointModelNames());
92  }
93 
94  bp::list getGroupJointNames(const std::string& group) const
95  {
96  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
97  if (jmg)
99  else
100  return bp::list();
101  }
102 
103  bp::list getGroupJointTips(const std::string& group) const
104  {
105  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
106  if (jmg)
107  {
108  std::vector<std::string> tips;
109  jmg->getEndEffectorTips(tips);
111  }
112  else
113  return bp::list();
114  }
115 
116  bp::list getLinkNames() const
117  {
118  return py_bindings_tools::listFromString(robot_model_->getLinkModelNames());
119  }
120 
121  bp::list getGroupLinkNames(const std::string& group) const
122  {
123  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
124  if (jmg)
126  else
127  return bp::list();
128  }
129 
130  bp::list getGroupNames() const
131  {
132  return py_bindings_tools::listFromString(robot_model_->getJointModelGroupNames());
133  }
134 
135  bp::list getJointLimits(const std::string& name) const
136  {
137  bp::list result;
138  const moveit::core::JointModel* jm = robot_model_->getJointModel(name);
139  if (jm)
140  {
141  const std::vector<moveit_msgs::msg::JointLimits>& lim = jm->getVariableBoundsMsg();
142  for (const moveit_msgs::msg::JointLimits& joint_limit : lim)
143  {
144  bp::list l;
145  l.append(joint_limit.min_position);
146  l.append(joint_limit.max_position);
147  result.append(l);
148  }
149  }
150  return result;
151  }
152 
153  const char* getPlanningFrame() const
154  {
155  return robot_model_->getModelFrame().c_str();
156  }
157 
158  bp::list getLinkPose(const std::string& name)
159  {
160  bp::list l;
161  if (!ensureCurrentState())
162  return l;
163  moveit::core::RobotStatePtr state = current_state_monitor_->getCurrentState();
164  const moveit::core::LinkModel* lm = state->getLinkModel(name);
165  if (lm)
166  {
167  // getGlobalLinkTransform() returns a valid isometry by contract
168  const Eigen::Isometry3d& t = state->getGlobalLinkTransform(lm);
169  std::vector<double> v(7);
170  v[0] = t.translation().x();
171  v[1] = t.translation().y();
172  v[2] = t.translation().z();
173  Eigen::Quaterniond q(t.linear());
174  v[3] = q.x();
175  v[4] = q.y();
176  v[5] = q.z();
177  v[6] = q.w();
179  }
180  return l;
181  }
182 
183  bp::list getDefaultStateNames(const std::string& group)
184  {
185  bp::list l;
186  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
187  if (jmg)
188  {
189  for (auto& known_state : jmg->getDefaultStateNames())
190  {
191  l.append(known_state);
192  }
193  }
194  return l;
195  }
196 
197  bp::list getCurrentJointValues(const std::string& name)
198  {
199  bp::list l;
200  if (!ensureCurrentState())
201  return l;
202  moveit::core::RobotStatePtr state = current_state_monitor_->getCurrentState();
203  const moveit::core::JointModel* jm = state->getJointModel(name);
204  if (jm)
205  {
206  const double* pos = state->getJointPositions(jm);
207  const unsigned int sz = jm->getVariableCount();
208  for (unsigned int i = 0; i < sz; ++i)
209  l.append(pos[i]);
210  }
211 
212  return l;
213  }
214 
215  bp::dict getJointValues(const std::string& group, const std::string& named_state)
216  {
217  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
218  if (!jmg)
219  return boost::python::dict();
220  std::map<std::string, double> values;
221  jmg->getVariableDefaultPositions(named_state, values);
222  return py_bindings_tools::dictFromType(values);
223  }
224 
225  bool ensureCurrentState(double wait = 1.0)
226  {
227  if (!current_state_monitor_)
228  {
229  ROS_ERROR("Unable to get current robot state");
230  return false;
231  }
232 
233  // if needed, start the monitor and wait up to 1 second for a full robot state
234  if (!current_state_monitor_->isActive())
235  {
236  GILReleaser gr;
237  current_state_monitor_->startStateMonitor();
238  if (!current_state_monitor_->waitForCompleteState(wait))
239  ROS_WARN("Joint values for monitored state are requested but the full state is not known");
240  }
241  return true;
242  }
243 
244  py_bindings_tools::ByteString getCurrentState()
245  {
246  if (!ensureCurrentState())
247  return py_bindings_tools::ByteString("");
248  moveit::core::RobotStatePtr s = current_state_monitor_->getCurrentState();
249  moveit_msgs::msg::RobotState msg;
252  }
253 
254  bp::tuple getEndEffectorParentGroup(const std::string& group)
255  {
256  // name of the group that is parent to this end-effector group;
257  // Second: the link this in the parent group that this group attaches to
258  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
259  if (!jmg)
260  return boost::python::make_tuple("", "");
261  std::pair<std::string, std::string> parent_group = jmg->getEndEffectorParentGroup();
262  return boost::python::make_tuple(parent_group.first, parent_group.second);
263  }
264 
265  py_bindings_tools::ByteString getRobotMarkersPythonDictList(bp::dict& values, bp::list& links)
266  {
267  moveit::core::RobotStatePtr state;
268  if (ensureCurrentState())
269  {
270  state = current_state_monitor_->getCurrentState();
271  }
272  else
273  {
274  state = std::make_shared<moveit::core::RobotState>(robot_model_);
275  }
276 
277  bp::list k = values.keys();
278  int l = bp::len(k);
279  sensor_msgs::JointState joint_state;
280  joint_state.name.resize(l);
281  joint_state.position.resize(l);
282  for (int i = 0; i < l; ++i)
283  {
284  joint_state.name[i] = bp::extract<std::string>(k[i]);
285  joint_state.position[i] = bp::extract<double>(values[k[i]]);
286  }
287  state->setVariableValues(joint_state);
288  visualization_msgs::MarkerArray msg;
289  state->getRobotMarkers(msg, py_bindings_tools::stringFromList(links));
290 
292  }
293 
294  py_bindings_tools::ByteString getRobotMarkersPythonDict(bp::dict& values)
295  {
296  bp::list links = py_bindings_tools::listFromString(robot_model_->getLinkModelNames());
297  return getRobotMarkersPythonDictList(values, links);
298  }
299 
300  py_bindings_tools::ByteString getRobotMarkersFromMsg(const py_bindings_tools::ByteString& state_str)
301  {
302  moveit_msgs::msg::RobotState state_msg;
303  moveit::core::RobotState state(robot_model_);
304  py_bindings_tools::deserializeMsg(state_str, state_msg);
305  moveit::core::robotStateMsgToRobotState(state_msg, state);
306 
307  visualization_msgs::MarkerArray msg;
308  state.getRobotMarkers(msg, state.getRobotModel()->getLinkModelNames());
309 
311  }
312 
313  py_bindings_tools::ByteString getRobotMarkers()
314  {
315  if (!ensureCurrentState())
316  return py_bindings_tools::ByteString();
317  moveit::core::RobotStatePtr s = current_state_monitor_->getCurrentState();
318  visualization_msgs::MarkerArray msg;
319  s->getRobotMarkers(msg, s->getRobotModel()->getLinkModelNames());
320 
322  }
323 
324  py_bindings_tools::ByteString getRobotMarkersPythonList(const bp::list& links)
325  {
326  if (!ensureCurrentState())
327  return py_bindings_tools::ByteString("");
328  moveit::core::RobotStatePtr s = current_state_monitor_->getCurrentState();
329  visualization_msgs::MarkerArray msg;
330  s->getRobotMarkers(msg, py_bindings_tools::stringFromList(links));
331 
333  }
334 
335  py_bindings_tools::ByteString getRobotMarkersGroup(const std::string& group)
336  {
337  if (!ensureCurrentState())
338  return py_bindings_tools::ByteString("");
339  moveit::core::RobotStatePtr s = current_state_monitor_->getCurrentState();
340  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
341  visualization_msgs::MarkerArray msg;
342  if (jmg)
343  {
344  s->getRobotMarkers(msg, jmg->getLinkModelNames());
345  }
346 
348  }
349 
350  py_bindings_tools::ByteString getRobotMarkersGroupPythonDict(const std::string& group, bp::dict& values)
351  {
352  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
353  if (!jmg)
354  return py_bindings_tools::ByteString("");
355  bp::list links = py_bindings_tools::listFromString(jmg->getLinkModelNames());
356  return getRobotMarkersPythonDictList(values, links);
357  }
358 
359  bp::dict getCurrentVariableValues()
360  {
361  bp::dict d;
362 
363  if (!ensureCurrentState())
364  return d;
365 
366  const std::map<std::string, double>& vars = current_state_monitor_->getCurrentStateValues();
367  for (const std::pair<const std::string, double>& var : vars)
368  d[var.first] = var.second;
369 
370  return d;
371  }
372 
373  const char* getRobotRootLink() const
374  {
375  return robot_model_->getRootLinkName().c_str();
376  }
377 
378  bool hasGroup(const std::string& group) const
379  {
380  return robot_model_->hasJointModelGroup(group);
381  }
382 
383 private:
384  moveit::core::RobotModelConstPtr robot_model_;
385  planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_;
386  ros::NodeHandle nh_;
387 };
388 } // namespace moveit
389 
390 static void wrap_robot_interface()
391 {
392  using namespace moveit;
393 
394  bp::class_<RobotInterfacePython> robot_class("RobotInterface", bp::init<std::string, bp::optional<std::string>>());
395 
396  robot_class.def("get_joint_names", &RobotInterfacePython::getJointNames);
397  robot_class.def("get_group_joint_names", &RobotInterfacePython::getGroupJointNames);
398  robot_class.def("get_active_joint_names", &RobotInterfacePython::getActiveJointNames);
399  robot_class.def("get_group_active_joint_names", &RobotInterfacePython::getGroupActiveJointNames);
400  robot_class.def("get_group_default_states", &RobotInterfacePython::getDefaultStateNames);
401  robot_class.def("get_group_joint_tips", &RobotInterfacePython::getGroupJointTips);
402  robot_class.def("get_group_names", &RobotInterfacePython::getGroupNames);
403  robot_class.def("get_link_names", &RobotInterfacePython::getLinkNames);
404  robot_class.def("get_group_link_names", &RobotInterfacePython::getGroupLinkNames);
405  robot_class.def("get_joint_limits", &RobotInterfacePython::getJointLimits);
406  robot_class.def("get_link_pose", &RobotInterfacePython::getLinkPose);
407  robot_class.def("get_planning_frame", &RobotInterfacePython::getPlanningFrame);
408  robot_class.def("get_current_state", &RobotInterfacePython::getCurrentState);
409  robot_class.def("get_current_variable_values", &RobotInterfacePython::getCurrentVariableValues);
410  robot_class.def("get_current_joint_values", &RobotInterfacePython::getCurrentJointValues);
411  robot_class.def("get_joint_values", &RobotInterfacePython::getJointValues);
412  robot_class.def("get_robot_root_link", &RobotInterfacePython::getRobotRootLink);
413  robot_class.def("has_group", &RobotInterfacePython::hasGroup);
414  robot_class.def("get_robot_name", &RobotInterfacePython::getRobotName);
415  robot_class.def("get_robot_markers", &RobotInterfacePython::getRobotMarkers);
416  robot_class.def("get_robot_markers", &RobotInterfacePython::getRobotMarkersPythonList);
417  robot_class.def("get_robot_markers", &RobotInterfacePython::getRobotMarkersFromMsg);
418  robot_class.def("get_robot_markers", &RobotInterfacePython::getRobotMarkersPythonDictList);
419  robot_class.def("get_robot_markers", &RobotInterfacePython::getRobotMarkersPythonDict);
420  robot_class.def("get_group_markers", &RobotInterfacePython::getRobotMarkersGroup);
421  robot_class.def("get_group_markers", &RobotInterfacePython::getRobotMarkersGroupPythonDict);
422  robot_class.def("get_parent_group", &RobotInterfacePython::getEndEffectorParentGroup);
423 }
424 
425 BOOST_PYTHON_MODULE(_moveit_robot_interface)
426 {
427  wrap_robot_interface();
428 }
429 
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool getEndEffectorTips(std::vector< const LinkModel * > &tips) const
Get the unique set of end effector tips included in a particular joint model group as defined by the ...
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
Get the name of the group this end-effector attaches to (first) and the name of the link in that grou...
bool getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const
Get the values that correspond to a named state as read from the URDF. Return false on failure.
const std::vector< std::string > & getDefaultStateNames() const
Get the names of the known default states (as specified in the SRDF)
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
const std::vector< moveit_msgs::msg::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
Definition: joint_model.h:344
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
RAII Helper to release the Global Interpreter Lock (GIL)
Definition: gil_releaser.h:55
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
moveit::core::RobotModelConstPtr getSharedRobotModel(const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
getSharedStateMonitor
boost::python::list listFromString(const std::vector< std::string > &v)
boost::python::list listFromDouble(const std::vector< double > &v)
boost::python::dict dictFromType(const std::map< std::string, T > &v)
ByteString serializeMsg(const T &msg)
Convert a ROS message to a Python Bytestring.
std::vector< std::string > stringFromList(const boost::python::object &values)
void deserializeMsg(const ByteString &data, T &msg)
Convert a Python Bytestring to a ROS message.
Main namespace for MoveIt.
Definition: exceptions.h:43
bool getJointLimits(const std::string &joint_name, const std::string &param_ns, const rclcpp::Node::SharedPtr &node, joint_limits_interface::JointLimits &limits)
d
Definition: setup.py:4
name
Definition: setup.py:7
BOOST_PYTHON_MODULE(_moveit_roscpp_initializer)