-
Notifications
You must be signed in to change notification settings - Fork 938
/
wrap_python_move_group.cpp
662 lines (574 loc) · 27.4 KB
/
wrap_python_move_group.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan */
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/py_bindings_tools/roscpp_initializer.h>
#include <moveit/py_bindings_tools/py_conversions.h>
#include <moveit/py_bindings_tools/serialize_msg.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
#include <tf2_eigen/tf2_eigen.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/buffer.h>
#include <boost/python.hpp>
#include <memory>
#include <Python.h>
/** @cond IGNORE */
namespace bp = boost::python;
namespace moveit
{
namespace planning_interface
{
class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer, public MoveGroupInterface
{
public:
// ROSInitializer is constructed first, and ensures ros::init() was called, if
// needed
MoveGroupInterfaceWrapper(const std::string& group_name, const std::string& robot_description,
const std::string& ns = "", double wait_for_servers = 5.0)
: py_bindings_tools::ROScppInitializer()
, MoveGroupInterface(Options(group_name, robot_description, ros::NodeHandle(ns)),
std::shared_ptr<tf2_ros::Buffer>(), ros::WallDuration(wait_for_servers))
{
}
bool setJointValueTargetPerJointPythonList(const std::string& joint, bp::list& values)
{
return setJointValueTarget(joint, py_bindings_tools::doubleFromList(values));
}
bool setJointValueTargetPythonIterable(bp::object& values)
{
return setJointValueTarget(py_bindings_tools::doubleFromList(values));
}
bool setJointValueTargetPythonDict(bp::dict& values)
{
bp::list k = values.keys();
int l = bp::len(k);
std::map<std::string, double> v;
for (int i = 0; i < l; ++i)
v[bp::extract<std::string>(k[i])] = bp::extract<double>(values[k[i]]);
return setJointValueTarget(v);
}
bool setJointValueTargetFromPosePython(const std::string& pose_str, const std::string& eef, bool approx)
{
geometry_msgs::Pose pose_msg;
py_bindings_tools::deserializeMsg(pose_str, pose_msg);
return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
}
bool setJointValueTargetFromPoseStampedPython(const std::string& pose_str, const std::string& eef, bool approx)
{
geometry_msgs::PoseStamped pose_msg;
py_bindings_tools::deserializeMsg(pose_str, pose_msg);
return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
}
bool setJointValueTargetFromJointStatePython(const std::string& js_str)
{
sensor_msgs::JointState js_msg;
py_bindings_tools::deserializeMsg(js_str, js_msg);
return setJointValueTarget(js_msg);
}
bp::list getJointValueTargetPythonList()
{
std::vector<double> values;
MoveGroupInterface::getJointValueTarget(values);
bp::list l;
for (const double value : values)
l.append(value);
return l;
}
std::string getJointValueTarget()
{
moveit_msgs::RobotState msg;
const robot_state::RobotState state = moveit::planning_interface::MoveGroupInterface::getTargetRobotState();
moveit::core::robotStateToRobotStateMsg(state, msg);
return py_bindings_tools::serializeMsg(msg);
}
void rememberJointValuesFromPythonList(const std::string& string, bp::list& values)
{
rememberJointValues(string, py_bindings_tools::doubleFromList(values));
}
const char* getPlanningFrameCStr() const
{
return getPlanningFrame().c_str();
}
std::string getInterfaceDescriptionPython()
{
moveit_msgs::PlannerInterfaceDescription msg;
getInterfaceDescription(msg);
return py_bindings_tools::serializeMsg(msg);
}
bp::list getActiveJointsList() const
{
return py_bindings_tools::listFromString(getActiveJoints());
}
bp::list getJointsList() const
{
return py_bindings_tools::listFromString(getJoints());
}
bp::list getCurrentJointValuesList()
{
return py_bindings_tools::listFromDouble(getCurrentJointValues());
}
bp::list getRandomJointValuesList()
{
return py_bindings_tools::listFromDouble(getRandomJointValues());
}
bp::dict getRememberedJointValuesPython() const
{
const std::map<std::string, std::vector<double>>& rv = getRememberedJointValues();
bp::dict d;
for (const std::pair<const std::string, std::vector<double>>& it : rv)
d[it.first] = py_bindings_tools::listFromDouble(it.second);
return d;
}
bp::list convertPoseToList(const geometry_msgs::Pose& pose) const
{
std::vector<double> v(7);
v[0] = pose.position.x;
v[1] = pose.position.y;
v[2] = pose.position.z;
v[3] = pose.orientation.x;
v[4] = pose.orientation.y;
v[5] = pose.orientation.z;
v[6] = pose.orientation.w;
return moveit::py_bindings_tools::listFromDouble(v);
}
bp::list convertTransformToList(const geometry_msgs::Transform& tr) const
{
std::vector<double> v(7);
v[0] = tr.translation.x;
v[1] = tr.translation.y;
v[2] = tr.translation.z;
v[3] = tr.rotation.x;
v[4] = tr.rotation.y;
v[5] = tr.rotation.z;
v[6] = tr.rotation.w;
return py_bindings_tools::listFromDouble(v);
}
void convertListToTransform(const bp::list& l, geometry_msgs::Transform& tr) const
{
std::vector<double> v = py_bindings_tools::doubleFromList(l);
tr.translation.x = v[0];
tr.translation.y = v[1];
tr.translation.z = v[2];
tr.rotation.x = v[3];
tr.rotation.y = v[4];
tr.rotation.z = v[5];
tr.rotation.w = v[6];
}
void convertListToPose(const bp::list& l, geometry_msgs::Pose& p) const
{
std::vector<double> v = py_bindings_tools::doubleFromList(l);
p.position.x = v[0];
p.position.y = v[1];
p.position.z = v[2];
p.orientation.x = v[3];
p.orientation.y = v[4];
p.orientation.z = v[5];
p.orientation.w = v[6];
}
bp::list getCurrentRPYPython(const std::string& end_effector_link = "")
{
return py_bindings_tools::listFromDouble(getCurrentRPY(end_effector_link));
}
bp::list getCurrentPosePython(const std::string& end_effector_link = "")
{
geometry_msgs::PoseStamped pose = getCurrentPose(end_effector_link);
return convertPoseToList(pose.pose);
}
bp::list getRandomPosePython(const std::string& end_effector_link = "")
{
geometry_msgs::PoseStamped pose = getRandomPose(end_effector_link);
return convertPoseToList(pose.pose);
}
bp::list getKnownConstraintsList() const
{
return py_bindings_tools::listFromString(getKnownConstraints());
}
bool placePose(const std::string& object_name, const bp::list& pose, bool plan_only = false)
{
geometry_msgs::PoseStamped msg;
convertListToPose(pose, msg.pose);
msg.header.frame_id = getPoseReferenceFrame();
msg.header.stamp = ros::Time::now();
return place(object_name, msg, plan_only) == MoveItErrorCode::SUCCESS;
}
bool placeLocation(const std::string& object_name, const std::string& location_str, bool plan_only = false)
{
std::vector<moveit_msgs::PlaceLocation> locations(1);
py_bindings_tools::deserializeMsg(location_str, locations[0]);
return place(object_name, locations, plan_only) == MoveItErrorCode::SUCCESS;
}
bool placeAnywhere(const std::string& object_name, bool plan_only = false)
{
return place(object_name, plan_only) == MoveItErrorCode::SUCCESS;
}
void convertListToArrayOfPoses(const bp::list& poses, std::vector<geometry_msgs::Pose>& msg)
{
int l = bp::len(poses);
for (int i = 0; i < l; ++i)
{
const bp::list& pose = bp::extract<bp::list>(poses[i]);
std::vector<double> v = py_bindings_tools::doubleFromList(pose);
if (v.size() == 6 || v.size() == 7)
{
Eigen::Isometry3d p;
if (v.size() == 6)
{
tf2::Quaternion tq;
tq.setRPY(v[3], v[4], v[5]);
Eigen::Quaterniond eq;
tf2::convert(tq, eq);
p = Eigen::Isometry3d(eq);
}
else
p = Eigen::Isometry3d(Eigen::Quaterniond(v[6], v[3], v[4], v[5]));
p.translation() = Eigen::Vector3d(v[0], v[1], v[2]);
geometry_msgs::Pose pm = tf2::toMsg(p);
msg.push_back(pm);
}
else
ROS_WARN("Incorrect number of values for a pose: %u", (unsigned int)v.size());
}
}
bp::dict getCurrentStateBoundedPython()
{
robot_state::RobotStatePtr current = getCurrentState();
current->enforceBounds();
moveit_msgs::RobotState rsmv;
robot_state::robotStateToRobotStateMsg(*current, rsmv);
bp::dict output;
for (size_t x = 0; x < rsmv.joint_state.name.size(); ++x)
output[rsmv.joint_state.name[x]] = rsmv.joint_state.position[x];
return output;
}
void setStartStatePython(const std::string& msg_str)
{
moveit_msgs::RobotState msg;
py_bindings_tools::deserializeMsg(msg_str, msg);
setStartState(msg);
}
bool setPoseTargetsPython(bp::list& poses, const std::string& end_effector_link = "")
{
std::vector<geometry_msgs::Pose> msg;
convertListToArrayOfPoses(poses, msg);
return setPoseTargets(msg, end_effector_link);
}
std::string getPoseTargetPython(const std::string& end_effector_link)
{
geometry_msgs::PoseStamped pose = moveit::planning_interface::MoveGroupInterface::getPoseTarget(end_effector_link);
return py_bindings_tools::serializeMsg(pose);
}
bool setPoseTargetPython(bp::list& pose, const std::string& end_effector_link = "")
{
std::vector<double> v = py_bindings_tools::doubleFromList(pose);
geometry_msgs::Pose msg;
if (v.size() == 6)
{
tf2::Quaternion q;
q.setRPY(v[3], v[4], v[5]);
tf2::convert(q, msg.orientation);
}
else if (v.size() == 7)
{
msg.orientation.x = v[3];
msg.orientation.y = v[4];
msg.orientation.z = v[5];
msg.orientation.w = v[6];
}
else
{
ROS_ERROR("Pose description expected to consist of either 6 or 7 values");
return false;
}
msg.position.x = v[0];
msg.position.y = v[1];
msg.position.z = v[2];
return setPoseTarget(msg, end_effector_link);
}
const char* getEndEffectorLinkCStr() const
{
return getEndEffectorLink().c_str();
}
const char* getPoseReferenceFrameCStr() const
{
return getPoseReferenceFrame().c_str();
}
const char* getNameCStr() const
{
return getName().c_str();
}
bp::dict getNamedTargetValuesPython(const std::string& name)
{
bp::dict output;
std::map<std::string, double> positions = getNamedTargetValues(name);
std::map<std::string, double>::iterator iterator;
for (iterator = positions.begin(); iterator != positions.end(); ++iterator)
output[iterator->first] = iterator->second;
return output;
}
bp::list getNamedTargetsPython()
{
return py_bindings_tools::listFromString(getNamedTargets());
}
bool movePython()
{
return move() == MoveItErrorCode::SUCCESS;
}
bool asyncMovePython()
{
return asyncMove() == MoveItErrorCode::SUCCESS;
}
bool attachObjectPython(const std::string& object_name, const std::string& link_name, const bp::list& touch_links)
{
return attachObject(object_name, link_name, py_bindings_tools::stringFromList(touch_links));
}
bool executePython(const std::string& plan_str)
{
MoveGroupInterface::Plan plan;
py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
return execute(plan) == MoveItErrorCode::SUCCESS;
}
bool asyncExecutePython(const std::string& plan_str)
{
MoveGroupInterface::Plan plan;
py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
return asyncExecute(plan) == MoveItErrorCode::SUCCESS;
}
bp::tuple planPython()
{
MoveGroupInterface::Plan plan;
moveit_msgs::MoveItErrorCodes res = MoveGroupInterface::plan(plan);
return bp::make_tuple(py_bindings_tools::serializeMsg(res), py_bindings_tools::serializeMsg(plan.trajectory_),
plan.planning_time_);
}
bp::tuple computeCartesianPathPython(const bp::list& waypoints, double eef_step, double jump_threshold,
bool avoid_collisions)
{
moveit_msgs::Constraints path_constraints_tmp;
return doComputeCartesianPathPython(waypoints, eef_step, jump_threshold, avoid_collisions, path_constraints_tmp);
}
bp::tuple computeCartesianPathConstrainedPython(const bp::list& waypoints, double eef_step, double jump_threshold,
bool avoid_collisions, const std::string& path_constraints_str)
{
moveit_msgs::Constraints path_constraints;
py_bindings_tools::deserializeMsg(path_constraints_str, path_constraints);
return doComputeCartesianPathPython(waypoints, eef_step, jump_threshold, avoid_collisions, path_constraints);
}
bp::tuple doComputeCartesianPathPython(const bp::list& waypoints, double eef_step, double jump_threshold,
bool avoid_collisions, const moveit_msgs::Constraints& path_constraints)
{
std::vector<geometry_msgs::Pose> poses;
convertListToArrayOfPoses(waypoints, poses);
moveit_msgs::RobotTrajectory trajectory;
double fraction =
computeCartesianPath(poses, eef_step, jump_threshold, trajectory, path_constraints, avoid_collisions);
return bp::make_tuple(py_bindings_tools::serializeMsg(trajectory), fraction);
}
int pickGrasp(const std::string& object, const std::string& grasp_str, bool plan_only = false)
{
moveit_msgs::Grasp grasp;
py_bindings_tools::deserializeMsg(grasp_str, grasp);
return pick(object, grasp, plan_only).val;
}
int pickGrasps(const std::string& object, const bp::list& grasp_list, bool plan_only = false)
{
int l = bp::len(grasp_list);
std::vector<moveit_msgs::Grasp> grasps(l);
for (int i = 0; i < l; ++i)
py_bindings_tools::deserializeMsg(bp::extract<std::string>(grasp_list[i]), grasps[i]);
return pick(object, grasps, plan_only).val;
}
void setPathConstraintsFromMsg(const std::string& constraints_str)
{
moveit_msgs::Constraints constraints_msg;
py_bindings_tools::deserializeMsg(constraints_str, constraints_msg);
setPathConstraints(constraints_msg);
}
std::string getPathConstraintsPython()
{
moveit_msgs::Constraints constraints_msg(getPathConstraints());
std::string constraints_str = py_bindings_tools::serializeMsg(constraints_msg);
return constraints_str;
}
std::string retimeTrajectory(const std::string& ref_state_str, const std::string& traj_str,
double velocity_scaling_factor)
{
// Convert reference state message to object
moveit_msgs::RobotState ref_state_msg;
py_bindings_tools::deserializeMsg(ref_state_str, ref_state_msg);
moveit::core::RobotState ref_state_obj(getRobotModel());
if (moveit::core::robotStateMsgToRobotState(ref_state_msg, ref_state_obj, true))
{
// Convert trajectory message to object
moveit_msgs::RobotTrajectory traj_msg;
py_bindings_tools::deserializeMsg(traj_str, traj_msg);
robot_trajectory::RobotTrajectory traj_obj(getRobotModel(), getName());
traj_obj.setRobotTrajectoryMsg(ref_state_obj, traj_msg);
// Do the actual retiming
trajectory_processing::IterativeParabolicTimeParameterization time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor);
// Convert the retimed trajectory back into a message
traj_obj.getRobotTrajectoryMsg(traj_msg);
std::string traj_str = py_bindings_tools::serializeMsg(traj_msg);
// Return it.
return traj_str;
}
else
{
ROS_ERROR("Unable to convert RobotState message to RobotState instance.");
return "";
}
}
};
static void wrap_move_group_interface()
{
bp::class_<MoveGroupInterfaceWrapper, boost::noncopyable> move_group_interface_class(
"MoveGroupInterface", bp::init<std::string, std::string, bp::optional<std::string>>());
move_group_interface_class.def("async_move", &MoveGroupInterfaceWrapper::asyncMovePython);
move_group_interface_class.def("move", &MoveGroupInterfaceWrapper::movePython);
move_group_interface_class.def("execute", &MoveGroupInterfaceWrapper::executePython);
move_group_interface_class.def("async_execute", &MoveGroupInterfaceWrapper::asyncExecutePython);
moveit::planning_interface::MoveItErrorCode (MoveGroupInterfaceWrapper::*pick_1)(const std::string&, bool) =
&MoveGroupInterfaceWrapper::pick;
move_group_interface_class.def("pick", pick_1);
move_group_interface_class.def("pick", &MoveGroupInterfaceWrapper::pickGrasp);
move_group_interface_class.def("pick", &MoveGroupInterfaceWrapper::pickGrasps);
move_group_interface_class.def("place", &MoveGroupInterfaceWrapper::placePose);
move_group_interface_class.def("place", &MoveGroupInterfaceWrapper::placeLocation);
move_group_interface_class.def("place", &MoveGroupInterfaceWrapper::placeAnywhere);
move_group_interface_class.def("stop", &MoveGroupInterfaceWrapper::stop);
move_group_interface_class.def("get_name", &MoveGroupInterfaceWrapper::getNameCStr);
move_group_interface_class.def("get_planning_frame", &MoveGroupInterfaceWrapper::getPlanningFrameCStr);
move_group_interface_class.def("get_interface_description",
&MoveGroupInterfaceWrapper::getInterfaceDescriptionPython);
move_group_interface_class.def("get_active_joints", &MoveGroupInterfaceWrapper::getActiveJointsList);
move_group_interface_class.def("get_joints", &MoveGroupInterfaceWrapper::getJointsList);
move_group_interface_class.def("get_variable_count", &MoveGroupInterfaceWrapper::getVariableCount);
move_group_interface_class.def("allow_looking", &MoveGroupInterfaceWrapper::allowLooking);
move_group_interface_class.def("allow_replanning", &MoveGroupInterfaceWrapper::allowReplanning);
move_group_interface_class.def("set_pose_reference_frame", &MoveGroupInterfaceWrapper::setPoseReferenceFrame);
move_group_interface_class.def("set_pose_reference_frame", &MoveGroupInterfaceWrapper::setPoseReferenceFrame);
move_group_interface_class.def("set_end_effector_link", &MoveGroupInterfaceWrapper::setEndEffectorLink);
move_group_interface_class.def("get_end_effector_link", &MoveGroupInterfaceWrapper::getEndEffectorLinkCStr);
move_group_interface_class.def("get_pose_reference_frame", &MoveGroupInterfaceWrapper::getPoseReferenceFrameCStr);
move_group_interface_class.def("set_pose_target", &MoveGroupInterfaceWrapper::setPoseTargetPython);
move_group_interface_class.def("set_pose_targets", &MoveGroupInterfaceWrapper::setPoseTargetsPython);
move_group_interface_class.def("set_position_target", &MoveGroupInterfaceWrapper::setPositionTarget);
move_group_interface_class.def("set_rpy_target", &MoveGroupInterfaceWrapper::setRPYTarget);
move_group_interface_class.def("set_orientation_target", &MoveGroupInterfaceWrapper::setOrientationTarget);
move_group_interface_class.def("get_current_pose", &MoveGroupInterfaceWrapper::getCurrentPosePython);
move_group_interface_class.def("get_current_rpy", &MoveGroupInterfaceWrapper::getCurrentRPYPython);
move_group_interface_class.def("get_random_pose", &MoveGroupInterfaceWrapper::getRandomPosePython);
move_group_interface_class.def("clear_pose_target", &MoveGroupInterfaceWrapper::clearPoseTarget);
move_group_interface_class.def("clear_pose_targets", &MoveGroupInterfaceWrapper::clearPoseTargets);
move_group_interface_class.def("set_joint_value_target",
&MoveGroupInterfaceWrapper::setJointValueTargetPythonIterable);
move_group_interface_class.def("set_joint_value_target", &MoveGroupInterfaceWrapper::setJointValueTargetPythonDict);
move_group_interface_class.def("set_joint_value_target",
&MoveGroupInterfaceWrapper::setJointValueTargetPerJointPythonList);
bool (MoveGroupInterfaceWrapper::*set_joint_value_target_4)(const std::string&, double) =
&MoveGroupInterfaceWrapper::setJointValueTarget;
move_group_interface_class.def("set_joint_value_target", set_joint_value_target_4);
move_group_interface_class.def("set_joint_value_target_from_pose",
&MoveGroupInterfaceWrapper::setJointValueTargetFromPosePython);
move_group_interface_class.def("set_joint_value_target_from_pose_stamped",
&MoveGroupInterfaceWrapper::setJointValueTargetFromPoseStampedPython);
move_group_interface_class.def("set_joint_value_target_from_joint_state_message",
&MoveGroupInterfaceWrapper::setJointValueTargetFromJointStatePython);
move_group_interface_class.def("get_joint_value_target", &MoveGroupInterfaceWrapper::getJointValueTargetPythonList);
move_group_interface_class.def("set_named_target", &MoveGroupInterfaceWrapper::setNamedTarget);
move_group_interface_class.def("set_random_target", &MoveGroupInterfaceWrapper::setRandomTarget);
void (MoveGroupInterfaceWrapper::*remember_joint_values_2)(const std::string&) =
&MoveGroupInterfaceWrapper::rememberJointValues;
move_group_interface_class.def("remember_joint_values", remember_joint_values_2);
move_group_interface_class.def("remember_joint_values",
&MoveGroupInterfaceWrapper::rememberJointValuesFromPythonList);
move_group_interface_class.def("start_state_monitor", &MoveGroupInterfaceWrapper::startStateMonitor);
move_group_interface_class.def("get_current_joint_values", &MoveGroupInterfaceWrapper::getCurrentJointValuesList);
move_group_interface_class.def("get_random_joint_values", &MoveGroupInterfaceWrapper::getRandomJointValuesList);
move_group_interface_class.def("get_remembered_joint_values",
&MoveGroupInterfaceWrapper::getRememberedJointValuesPython);
move_group_interface_class.def("forget_joint_values", &MoveGroupInterfaceWrapper::forgetJointValues);
move_group_interface_class.def("get_goal_joint_tolerance", &MoveGroupInterfaceWrapper::getGoalJointTolerance);
move_group_interface_class.def("get_goal_position_tolerance", &MoveGroupInterfaceWrapper::getGoalPositionTolerance);
move_group_interface_class.def("get_goal_orientation_tolerance",
&MoveGroupInterfaceWrapper::getGoalOrientationTolerance);
move_group_interface_class.def("set_goal_joint_tolerance", &MoveGroupInterfaceWrapper::setGoalJointTolerance);
move_group_interface_class.def("set_goal_position_tolerance", &MoveGroupInterfaceWrapper::setGoalPositionTolerance);
move_group_interface_class.def("set_goal_orientation_tolerance",
&MoveGroupInterfaceWrapper::setGoalOrientationTolerance);
move_group_interface_class.def("set_goal_tolerance", &MoveGroupInterfaceWrapper::setGoalTolerance);
move_group_interface_class.def("set_start_state_to_current_state",
&MoveGroupInterfaceWrapper::setStartStateToCurrentState);
move_group_interface_class.def("set_start_state", &MoveGroupInterfaceWrapper::setStartStatePython);
bool (MoveGroupInterfaceWrapper::*set_path_constraints_1)(const std::string&) =
&MoveGroupInterfaceWrapper::setPathConstraints;
move_group_interface_class.def("set_path_constraints", set_path_constraints_1);
move_group_interface_class.def("set_path_constraints_from_msg",
&MoveGroupInterfaceWrapper::setPathConstraintsFromMsg);
move_group_interface_class.def("get_path_constraints", &MoveGroupInterfaceWrapper::getPathConstraintsPython);
move_group_interface_class.def("clear_path_constraints", &MoveGroupInterfaceWrapper::clearPathConstraints);
move_group_interface_class.def("get_known_constraints", &MoveGroupInterfaceWrapper::getKnownConstraintsList);
move_group_interface_class.def("set_constraints_database", &MoveGroupInterfaceWrapper::setConstraintsDatabase);
move_group_interface_class.def("set_workspace", &MoveGroupInterfaceWrapper::setWorkspace);
move_group_interface_class.def("set_planning_time", &MoveGroupInterfaceWrapper::setPlanningTime);
move_group_interface_class.def("get_planning_time", &MoveGroupInterfaceWrapper::getPlanningTime);
move_group_interface_class.def("set_max_velocity_scaling_factor",
&MoveGroupInterfaceWrapper::setMaxVelocityScalingFactor);
move_group_interface_class.def("set_max_acceleration_scaling_factor",
&MoveGroupInterfaceWrapper::setMaxAccelerationScalingFactor);
move_group_interface_class.def("set_planner_id", &MoveGroupInterfaceWrapper::setPlannerId);
move_group_interface_class.def("set_num_planning_attempts", &MoveGroupInterfaceWrapper::setNumPlanningAttempts);
move_group_interface_class.def("plan", &MoveGroupInterfaceWrapper::planPython);
move_group_interface_class.def("compute_cartesian_path", &MoveGroupInterfaceWrapper::computeCartesianPathPython);
move_group_interface_class.def("compute_cartesian_path",
&MoveGroupInterfaceWrapper::computeCartesianPathConstrainedPython);
move_group_interface_class.def("set_support_surface_name", &MoveGroupInterfaceWrapper::setSupportSurfaceName);
move_group_interface_class.def("attach_object", &MoveGroupInterfaceWrapper::attachObjectPython);
move_group_interface_class.def("detach_object", &MoveGroupInterfaceWrapper::detachObject);
move_group_interface_class.def("retime_trajectory", &MoveGroupInterfaceWrapper::retimeTrajectory);
move_group_interface_class.def("get_named_targets", &MoveGroupInterfaceWrapper::getNamedTargetsPython);
move_group_interface_class.def("get_named_target_values", &MoveGroupInterfaceWrapper::getNamedTargetValuesPython);
move_group_interface_class.def("get_current_state_bounded", &MoveGroupInterfaceWrapper::getCurrentStateBoundedPython);
}
} // namespace planning_interface
} // namespace moveit
BOOST_PYTHON_MODULE(_moveit_move_group_interface)
{
using namespace moveit::planning_interface;
wrap_move_group_interface();
}
/** @endcond */