/
move_group_interface.cpp
2379 lines (2073 loc) · 78.5 KB
/
move_group_interface.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
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2014, SRI International
* Copyright (c) 2013, Ioan A. Sucan
* 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, Sachin Chitta */
#include <stdexcept>
#include <sstream>
#include <memory>
#include <moveit/warehouse/constraints_storage.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/move_group/capability_names.h>
#include <moveit/move_group_pick_place_capability/capability_names.h>
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/planning_scene_monitor/current_state_monitor.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit/trajectory_execution_manager/trajectory_execution_manager.h>
#include <moveit/common_planning_interface_objects/common_objects.h>
#include <moveit/robot_state/conversions.h>
#include <moveit_msgs/PickupAction.h>
#include <moveit_msgs/ExecuteTrajectoryAction.h>
#include <moveit_msgs/PlaceAction.h>
#include <moveit_msgs/ExecuteKnownTrajectory.h>
#include <moveit_msgs/QueryPlannerInterfaces.h>
#include <moveit_msgs/GetCartesianPath.h>
#include <moveit_msgs/GraspPlanning.h>
#include <moveit_msgs/GetPlannerParams.h>
#include <moveit_msgs/SetPlannerParams.h>
#include <std_msgs/String.h>
#include <geometry_msgs/TransformStamped.h>
#include <tf2/utils.h>
#include <tf2_eigen/tf2_eigen.h>
#include <tf2_ros/transform_listener.h>
#include <ros/console.h>
#include <ros/ros.h>
namespace moveit
{
namespace planning_interface
{
const std::string MoveGroupInterface::ROBOT_DESCRIPTION =
"robot_description"; // name of the robot description (a param name, so it can be changed externally)
const std::string GRASP_PLANNING_SERVICE_NAME = "plan_grasps"; // name of the service that can be used to plan grasps
const std::string LOGNAME = "move_group_interface";
namespace
{
enum ActiveTargetType
{
JOINT,
POSE,
POSITION,
ORIENTATION
};
}
class MoveGroupInterface::MoveGroupInterfaceImpl
{
friend MoveGroupInterface;
public:
MoveGroupInterfaceImpl(const Options& opt, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
const ros::WallDuration& wait_for_servers)
: opt_(opt), node_handle_(opt.node_handle_), tf_buffer_(tf_buffer)
{
robot_model_ = opt.robot_model_ ? opt.robot_model_ : getSharedRobotModel(opt.robot_description_);
if (!getRobotModel())
{
std::string error = "Unable to construct robot model. Please make sure all needed information is on the "
"parameter server.";
ROS_FATAL_STREAM_NAMED(LOGNAME, error);
throw std::runtime_error(error);
}
if (!getRobotModel()->hasJointModelGroup(opt.group_name_))
{
std::string error = "Group '" + opt.group_name_ + "' was not found.";
ROS_FATAL_STREAM_NAMED(LOGNAME, error);
throw std::runtime_error(error);
}
joint_model_group_ = getRobotModel()->getJointModelGroup(opt.group_name_);
joint_state_target_ = std::make_shared<moveit::core::RobotState>(getRobotModel());
joint_state_target_->setToDefaultValues();
active_target_ = JOINT;
can_look_ = false;
look_around_attempts_ = 0;
can_replan_ = false;
replan_delay_ = 2.0;
replan_attempts_ = 1;
allowed_planning_time_ = DEFAULT_ALLOWED_PLANNING_TIME;
num_planning_attempts_ = DEFAULT_NUM_PLANNING_ATTEMPTS;
max_cartesian_speed_ = 0.0;
std::string desc = opt.robot_description_.length() ? opt.robot_description_ : ROBOT_DESCRIPTION;
std::string kinematics_desc = desc + "_kinematics/";
node_handle_.param<double>(kinematics_desc + opt.group_name_ + "/goal_joint_tolerance", goal_joint_tolerance_,
DEFAULT_GOAL_JOINT_TOLERANCE);
node_handle_.param<double>(kinematics_desc + opt.group_name_ + "/goal_position_tolerance", goal_position_tolerance_,
DEFAULT_GOAL_POSITION_TOLERANCE);
node_handle_.param<double>(kinematics_desc + opt.group_name_ + "/goal_orientation_tolerance",
goal_orientation_tolerance_, DEFAULT_GOAL_ORIENTATION_TOLERANCE);
std::string planning_desc = desc + "_planning/";
node_handle_.param<double>(planning_desc + "default_velocity_scaling_factor", max_velocity_scaling_factor_, 0.1);
node_handle_.param<double>(planning_desc + "default_acceleration_scaling_factor", max_acceleration_scaling_factor_,
0.1);
initializing_constraints_ = false;
if (joint_model_group_->isChain())
end_effector_link_ = joint_model_group_->getLinkModelNames().back();
pose_reference_frame_ = getRobotModel()->getModelFrame();
trajectory_event_publisher_ = node_handle_.advertise<std_msgs::String>(
trajectory_execution_manager::TrajectoryExecutionManager::EXECUTION_EVENT_TOPIC, 1, false);
attached_object_publisher_ = node_handle_.advertise<moveit_msgs::AttachedCollisionObject>(
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC, 1, false);
current_state_monitor_ = getSharedStateMonitor(robot_model_, tf_buffer_, node_handle_);
ros::WallTime timeout_for_servers = ros::WallTime::now() + wait_for_servers;
if (wait_for_servers == ros::WallDuration())
timeout_for_servers = ros::WallTime(); // wait for ever
double allotted_time = wait_for_servers.toSec();
move_action_client_ = std::make_unique<actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction>>(
node_handle_, move_group::MOVE_ACTION, false);
waitForAction(move_action_client_, move_group::MOVE_ACTION, timeout_for_servers, allotted_time);
pick_action_client_ = std::make_unique<actionlib::SimpleActionClient<moveit_msgs::PickupAction>>(
node_handle_, move_group::PICKUP_ACTION, false);
waitForAction(pick_action_client_, move_group::PICKUP_ACTION, timeout_for_servers, allotted_time);
place_action_client_ = std::make_unique<actionlib::SimpleActionClient<moveit_msgs::PlaceAction>>(
node_handle_, move_group::PLACE_ACTION, false);
waitForAction(place_action_client_, move_group::PLACE_ACTION, timeout_for_servers, allotted_time);
execute_action_client_ = std::make_unique<actionlib::SimpleActionClient<moveit_msgs::ExecuteTrajectoryAction>>(
node_handle_, move_group::EXECUTE_ACTION_NAME, false);
waitForAction(execute_action_client_, move_group::EXECUTE_ACTION_NAME, timeout_for_servers, allotted_time);
query_service_ =
node_handle_.serviceClient<moveit_msgs::QueryPlannerInterfaces>(move_group::QUERY_PLANNERS_SERVICE_NAME);
get_params_service_ =
node_handle_.serviceClient<moveit_msgs::GetPlannerParams>(move_group::GET_PLANNER_PARAMS_SERVICE_NAME);
set_params_service_ =
node_handle_.serviceClient<moveit_msgs::SetPlannerParams>(move_group::SET_PLANNER_PARAMS_SERVICE_NAME);
cartesian_path_service_ =
node_handle_.serviceClient<moveit_msgs::GetCartesianPath>(move_group::CARTESIAN_PATH_SERVICE_NAME);
plan_grasps_service_ = node_handle_.serviceClient<moveit_msgs::GraspPlanning>(GRASP_PLANNING_SERVICE_NAME);
ROS_INFO_STREAM_NAMED(LOGNAME, "Ready to take commands for planning group " << opt.group_name_ << ".");
}
template <typename T>
void waitForAction(const T& action, const std::string& name, const ros::WallTime& timeout, double allotted_time) const
{
ROS_DEBUG_NAMED(LOGNAME, "Waiting for move_group action server (%s)...", name.c_str());
// wait for the server (and spin as needed)
if (timeout == ros::WallTime()) // wait forever
{
while (node_handle_.ok() && !action->isServerConnected())
{
ros::WallDuration(0.001).sleep();
// explicit ros::spinOnce on the callback queue used by NodeHandle that manages the action client
ros::CallbackQueue* queue = dynamic_cast<ros::CallbackQueue*>(node_handle_.getCallbackQueue());
if (queue)
{
queue->callAvailable();
}
else // in case of nodelets and specific callback queue implementations
{
ROS_WARN_ONCE_NAMED(LOGNAME, "Non-default CallbackQueue: Waiting for external queue "
"handling.");
}
}
}
else // wait with timeout
{
while (node_handle_.ok() && !action->isServerConnected() && timeout > ros::WallTime::now())
{
ros::WallDuration(0.001).sleep();
// explicit ros::spinOnce on the callback queue used by NodeHandle that manages the action client
ros::CallbackQueue* queue = dynamic_cast<ros::CallbackQueue*>(node_handle_.getCallbackQueue());
if (queue)
{
queue->callAvailable();
}
else // in case of nodelets and specific callback queue implementations
{
ROS_WARN_ONCE_NAMED(LOGNAME, "Non-default CallbackQueue: Waiting for external queue "
"handling.");
}
}
}
if (!action->isServerConnected())
{
std::stringstream error;
error << "Unable to connect to move_group action server '" << name << "' within allotted time (" << allotted_time
<< "s)";
throw std::runtime_error(error.str());
}
else
{
ROS_DEBUG_NAMED(LOGNAME, "Connected to '%s'", name.c_str());
}
}
~MoveGroupInterfaceImpl()
{
if (constraints_init_thread_)
constraints_init_thread_->join();
}
const std::shared_ptr<tf2_ros::Buffer>& getTF() const
{
return tf_buffer_;
}
const Options& getOptions() const
{
return opt_;
}
const moveit::core::RobotModelConstPtr& getRobotModel() const
{
return robot_model_;
}
const moveit::core::JointModelGroup* getJointModelGroup() const
{
return joint_model_group_;
}
actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction>& getMoveGroupClient() const
{
return *move_action_client_;
}
bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription& desc)
{
moveit_msgs::QueryPlannerInterfaces::Request req;
moveit_msgs::QueryPlannerInterfaces::Response res;
if (query_service_.call(req, res))
if (!res.planner_interfaces.empty())
{
desc = res.planner_interfaces.front();
return true;
}
return false;
}
bool getInterfaceDescriptions(std::vector<moveit_msgs::PlannerInterfaceDescription>& desc)
{
moveit_msgs::QueryPlannerInterfaces::Request req;
moveit_msgs::QueryPlannerInterfaces::Response res;
if (query_service_.call(req, res))
if (!res.planner_interfaces.empty())
{
desc = res.planner_interfaces;
return true;
}
return false;
}
std::map<std::string, std::string> getPlannerParams(const std::string& planner_id, const std::string& group = "")
{
moveit_msgs::GetPlannerParams::Request req;
moveit_msgs::GetPlannerParams::Response res;
req.planner_config = planner_id;
req.group = group;
std::map<std::string, std::string> result;
if (get_params_service_.call(req, res))
{
for (unsigned int i = 0, end = res.params.keys.size(); i < end; ++i)
result[res.params.keys[i]] = res.params.values[i];
}
return result;
}
void setPlannerParams(const std::string& planner_id, const std::string& group,
const std::map<std::string, std::string>& params, bool replace = false)
{
moveit_msgs::SetPlannerParams::Request req;
moveit_msgs::SetPlannerParams::Response res;
req.planner_config = planner_id;
req.group = group;
req.replace = replace;
for (const std::pair<const std::string, std::string>& param : params)
{
req.params.keys.push_back(param.first);
req.params.values.push_back(param.second);
}
set_params_service_.call(req, res);
}
std::string getDefaultPlanningPipelineId() const
{
std::string default_planning_pipeline;
node_handle_.getParam("move_group/default_planning_pipeline", default_planning_pipeline);
return default_planning_pipeline;
}
void setPlanningPipelineId(const std::string& pipeline_id)
{
if (pipeline_id != planning_pipeline_id_)
{
planning_pipeline_id_ = pipeline_id;
// Reset planner_id if planning pipeline changed
planner_id_ = "";
}
}
const std::string& getPlanningPipelineId() const
{
return planning_pipeline_id_;
}
std::string getDefaultPlannerId(const std::string& group) const
{
// Check what planning pipeline config should be used
std::string pipeline_id = getDefaultPlanningPipelineId();
if (!planning_pipeline_id_.empty())
pipeline_id = planning_pipeline_id_;
std::stringstream param_name;
param_name << "move_group";
if (!pipeline_id.empty())
param_name << "/planning_pipelines/" << pipeline_id;
if (!group.empty())
param_name << "/" << group;
param_name << "/default_planner_config";
std::string default_planner_config;
node_handle_.getParam(param_name.str(), default_planner_config);
return default_planner_config;
}
void setPlannerId(const std::string& planner_id)
{
planner_id_ = planner_id;
}
const std::string& getPlannerId() const
{
return planner_id_;
}
void setNumPlanningAttempts(unsigned int num_planning_attempts)
{
num_planning_attempts_ = num_planning_attempts;
}
void setMaxVelocityScalingFactor(double value)
{
setMaxScalingFactor(max_velocity_scaling_factor_, value, "velocity_scaling_factor", 0.1);
}
void setMaxAccelerationScalingFactor(double value)
{
setMaxScalingFactor(max_acceleration_scaling_factor_, value, "acceleration_scaling_factor", 0.1);
}
void setMaxScalingFactor(double& variable, const double target_value, const char* factor_name, double fallback_value)
{
if (target_value > 1.0)
{
ROS_WARN_NAMED(LOGNAME, "Limiting max_%s (%.2f) to 1.0.", factor_name, target_value);
variable = 1.0;
}
else if (target_value <= 0.0)
{
node_handle_.param<double>(std::string("robot_description_planning/default_") + factor_name, variable,
fallback_value);
if (target_value < 0.0)
{
ROS_WARN_NAMED(LOGNAME, "max_%s < 0.0! Setting to default: %.2f.", factor_name, variable);
}
}
else
{
variable = target_value;
}
}
void limitMaxCartesianLinkSpeed(const double max_speed, const std::string& link_name)
{
cartesian_speed_limited_link_ = link_name;
max_cartesian_speed_ = max_speed;
}
void clearMaxCartesianLinkSpeed()
{
cartesian_speed_limited_link_ = "";
max_cartesian_speed_ = 0.0;
}
moveit::core::RobotState& getTargetRobotState()
{
return *joint_state_target_;
}
const moveit::core::RobotState& getTargetRobotState() const
{
return *joint_state_target_;
}
void setStartState(const moveit::core::RobotState& start_state)
{
considered_start_state_ = std::make_shared<moveit::core::RobotState>(start_state);
}
void setStartStateToCurrentState()
{
considered_start_state_.reset();
}
moveit::core::RobotStatePtr getStartState()
{
if (considered_start_state_)
return considered_start_state_;
else
{
moveit::core::RobotStatePtr s;
getCurrentState(s);
return s;
}
}
bool setJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link,
const std::string& frame, bool approx)
{
const std::string& eef = end_effector_link.empty() ? getEndEffectorLink() : end_effector_link;
// this only works if we have an end-effector
if (!eef.empty())
{
// first we set the goal to be the same as the start state
moveit::core::RobotStatePtr c = getStartState();
if (c)
{
setTargetType(JOINT);
c->enforceBounds();
getTargetRobotState() = *c;
if (!getTargetRobotState().satisfiesBounds(getGoalJointTolerance()))
return false;
}
else
return false;
// we may need to do approximate IK
kinematics::KinematicsQueryOptions o;
o.return_approximate_solution = approx;
// if no frame transforms are needed, call IK directly
if (frame.empty() || moveit::core::Transforms::sameFrame(frame, getRobotModel()->getModelFrame()))
return getTargetRobotState().setFromIK(getJointModelGroup(), eef_pose, eef, 0.0,
moveit::core::GroupStateValidityCallbackFn(), o);
else
{
// transform the pose into the model frame, then do IK
bool frame_found;
const Eigen::Isometry3d& t = getTargetRobotState().getFrameTransform(frame, &frame_found);
if (frame_found)
{
Eigen::Isometry3d p;
tf2::fromMsg(eef_pose, p);
return getTargetRobotState().setFromIK(getJointModelGroup(), t * p, eef, 0.0,
moveit::core::GroupStateValidityCallbackFn(), o);
}
else
{
ROS_ERROR_NAMED(LOGNAME, "Unable to transform from frame '%s' to frame '%s'", frame.c_str(),
getRobotModel()->getModelFrame().c_str());
return false;
}
}
}
else
return false;
}
void setEndEffectorLink(const std::string& end_effector)
{
end_effector_link_ = end_effector;
}
void clearPoseTarget(const std::string& end_effector_link)
{
pose_targets_.erase(end_effector_link);
}
void clearPoseTargets()
{
pose_targets_.clear();
}
const std::string& getEndEffectorLink() const
{
return end_effector_link_;
}
const std::string& getEndEffector() const
{
if (!end_effector_link_.empty())
{
const std::vector<std::string>& possible_eefs =
getRobotModel()->getJointModelGroup(opt_.group_name_)->getAttachedEndEffectorNames();
for (const std::string& possible_eef : possible_eefs)
if (getRobotModel()->getEndEffector(possible_eef)->hasLinkModel(end_effector_link_))
return possible_eef;
}
static std::string empty;
return empty;
}
bool setPoseTargets(const std::vector<geometry_msgs::PoseStamped>& poses, const std::string& end_effector_link)
{
const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
if (eef.empty())
{
ROS_ERROR_NAMED(LOGNAME, "No end-effector to set the pose for");
return false;
}
else
{
pose_targets_[eef] = poses;
// make sure we don't store an actual stamp, since that will become stale can potentially cause tf errors
std::vector<geometry_msgs::PoseStamped>& stored_poses = pose_targets_[eef];
for (geometry_msgs::PoseStamped& stored_pose : stored_poses)
stored_pose.header.stamp = ros::Time(0);
}
return true;
}
bool hasPoseTarget(const std::string& end_effector_link) const
{
const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
return pose_targets_.find(eef) != pose_targets_.end();
}
const geometry_msgs::PoseStamped& getPoseTarget(const std::string& end_effector_link) const
{
const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
// if multiple pose targets are set, return the first one
std::map<std::string, std::vector<geometry_msgs::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
if (jt != pose_targets_.end())
if (!jt->second.empty())
return jt->second.at(0);
// or return an error
static const geometry_msgs::PoseStamped UNKNOWN;
ROS_ERROR_NAMED(LOGNAME, "Pose for end-effector '%s' not known.", eef.c_str());
return UNKNOWN;
}
const std::vector<geometry_msgs::PoseStamped>& getPoseTargets(const std::string& end_effector_link) const
{
const std::string& eef = end_effector_link.empty() ? end_effector_link_ : end_effector_link;
std::map<std::string, std::vector<geometry_msgs::PoseStamped>>::const_iterator jt = pose_targets_.find(eef);
if (jt != pose_targets_.end())
if (!jt->second.empty())
return jt->second;
// or return an error
static const std::vector<geometry_msgs::PoseStamped> EMPTY;
ROS_ERROR_NAMED(LOGNAME, "Poses for end-effector '%s' are not known.", eef.c_str());
return EMPTY;
}
void setPoseReferenceFrame(const std::string& pose_reference_frame)
{
pose_reference_frame_ = pose_reference_frame;
}
void setSupportSurfaceName(const std::string& support_surface)
{
support_surface_ = support_surface;
}
const std::string& getPoseReferenceFrame() const
{
return pose_reference_frame_;
}
void setTargetType(ActiveTargetType type)
{
active_target_ = type;
}
ActiveTargetType getTargetType() const
{
return active_target_;
}
bool startStateMonitor(double wait)
{
if (!current_state_monitor_)
{
ROS_ERROR_NAMED(LOGNAME, "Unable to monitor current robot state");
return false;
}
// if needed, start the monitor and wait up to 1 second for a full robot state
if (!current_state_monitor_->isActive())
current_state_monitor_->startStateMonitor();
current_state_monitor_->waitForCompleteState(opt_.group_name_, wait);
return true;
}
bool getCurrentState(moveit::core::RobotStatePtr& current_state, double wait_seconds = 1.0)
{
if (!current_state_monitor_)
{
ROS_ERROR_NAMED(LOGNAME, "Unable to get current robot state");
return false;
}
// if needed, start the monitor and wait up to 1 second for a full robot state
if (!current_state_monitor_->isActive())
current_state_monitor_->startStateMonitor();
if (!current_state_monitor_->waitForCurrentState(ros::Time::now(), wait_seconds))
{
ROS_ERROR_NAMED(LOGNAME, "Failed to fetch current robot state");
return false;
}
current_state = current_state_monitor_->getCurrentState();
return true;
}
/** \brief Convert a vector of PoseStamped to a vector of PlaceLocation */
std::vector<moveit_msgs::PlaceLocation>
posesToPlaceLocations(const std::vector<geometry_msgs::PoseStamped>& poses) const
{
std::vector<moveit_msgs::PlaceLocation> locations;
for (const geometry_msgs::PoseStamped& pose : poses)
{
moveit_msgs::PlaceLocation location;
location.pre_place_approach.direction.vector.z = -1.0;
location.post_place_retreat.direction.vector.x = -1.0;
location.pre_place_approach.direction.header.frame_id = getRobotModel()->getModelFrame();
location.post_place_retreat.direction.header.frame_id = end_effector_link_;
location.pre_place_approach.min_distance = 0.1;
location.pre_place_approach.desired_distance = 0.2;
location.post_place_retreat.min_distance = 0.0;
location.post_place_retreat.desired_distance = 0.2;
// location.post_place_posture is filled by the pick&place lib with the getDetachPosture from the AttachedBody
location.place_pose = pose;
locations.push_back(location);
}
ROS_DEBUG_NAMED(LOGNAME, "Move group interface has %u place locations", (unsigned int)locations.size());
return locations;
}
moveit::core::MoveItErrorCode place(const moveit_msgs::PlaceGoal& goal)
{
if (!place_action_client_)
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "place action client not found");
return moveit::core::MoveItErrorCode::FAILURE;
}
if (!place_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "place action server not connected");
return moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE;
}
place_action_client_->sendGoal(goal);
ROS_DEBUG_NAMED(LOGNAME, "Sent place goal with %d locations", (int)goal.place_locations.size());
if (!place_action_client_->waitForResult())
{
ROS_INFO_STREAM_NAMED(LOGNAME, "Place action returned early");
}
if (place_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
{
return place_action_client_->getResult()->error_code;
}
else
{
ROS_WARN_STREAM_NAMED(LOGNAME, "Fail: " << place_action_client_->getState().toString() << ": "
<< place_action_client_->getState().getText());
return place_action_client_->getResult()->error_code;
}
}
moveit::core::MoveItErrorCode pick(const moveit_msgs::PickupGoal& goal)
{
if (!pick_action_client_)
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "pick action client not found");
return moveit::core::MoveItErrorCode::FAILURE;
}
if (!pick_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "pick action server not connected");
return moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE;
}
pick_action_client_->sendGoal(goal);
if (!pick_action_client_->waitForResult())
{
ROS_INFO_STREAM_NAMED(LOGNAME, "Pickup action returned early");
}
if (pick_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
{
return pick_action_client_->getResult()->error_code;
}
else
{
ROS_WARN_STREAM_NAMED(LOGNAME, "Fail: " << pick_action_client_->getState().toString() << ": "
<< pick_action_client_->getState().getText());
return pick_action_client_->getResult()->error_code;
}
}
moveit::core::MoveItErrorCode planGraspsAndPick(const std::string& object, bool plan_only = false)
{
if (object.empty())
{
return planGraspsAndPick(moveit_msgs::CollisionObject());
}
PlanningSceneInterface psi;
std::map<std::string, moveit_msgs::CollisionObject> objects = psi.getObjects(std::vector<std::string>(1, object));
if (objects.empty())
{
ROS_ERROR_STREAM_NAMED(LOGNAME,
"Asked for grasps for the object '" << object << "', but the object could not be found");
return moveit::core::MoveItErrorCode::INVALID_OBJECT_NAME;
}
return planGraspsAndPick(objects[object], plan_only);
}
moveit::core::MoveItErrorCode planGraspsAndPick(const moveit_msgs::CollisionObject& object, bool plan_only = false)
{
if (!plan_grasps_service_.exists())
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "Grasp planning service '"
<< GRASP_PLANNING_SERVICE_NAME
<< "' is not available."
" This has to be implemented and started separately.");
return moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE;
}
moveit_msgs::GraspPlanning::Request request;
moveit_msgs::GraspPlanning::Response response;
request.group_name = opt_.group_name_;
request.target = object;
request.support_surfaces.push_back(support_surface_);
ROS_DEBUG_NAMED(LOGNAME, "Calling grasp planner...");
if (!plan_grasps_service_.call(request, response) ||
response.error_code.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
{
ROS_ERROR_NAMED(LOGNAME, "Grasp planning failed. Unable to pick.");
return moveit::core::MoveItErrorCode::FAILURE;
}
return pick(constructPickupGoal(object.id, std::move(response.grasps), plan_only));
}
moveit::core::MoveItErrorCode plan(Plan& plan)
{
if (!move_action_client_)
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "move action client not found");
return moveit::core::MoveItErrorCode::FAILURE;
}
if (!move_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "move action server not connected");
return moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE;
}
moveit_msgs::MoveGroupGoal goal;
constructGoal(goal);
goal.planning_options.plan_only = true;
goal.planning_options.look_around = false;
goal.planning_options.replan = false;
goal.planning_options.planning_scene_diff.is_diff = true;
goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
move_action_client_->sendGoal(goal);
if (!move_action_client_->waitForResult())
{
ROS_INFO_STREAM_NAMED(LOGNAME, "MoveGroup action returned early");
}
if (move_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
{
plan.trajectory_ = move_action_client_->getResult()->planned_trajectory;
plan.start_state_ = move_action_client_->getResult()->trajectory_start;
plan.planning_time_ = move_action_client_->getResult()->planning_time;
return move_action_client_->getResult()->error_code;
}
else
{
ROS_WARN_STREAM_NAMED(LOGNAME, "Fail: " << move_action_client_->getState().toString() << ": "
<< move_action_client_->getState().getText());
return move_action_client_->getResult()->error_code;
}
}
moveit::core::MoveItErrorCode move(bool wait)
{
if (!move_action_client_)
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "move action client not found");
return moveit::core::MoveItErrorCode::FAILURE;
}
if (!move_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "move action server not connected");
return moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE;
}
moveit_msgs::MoveGroupGoal goal;
constructGoal(goal);
goal.planning_options.plan_only = false;
goal.planning_options.look_around = can_look_;
goal.planning_options.replan = can_replan_;
goal.planning_options.replan_delay = replan_delay_;
goal.planning_options.planning_scene_diff.is_diff = true;
goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
move_action_client_->sendGoal(goal);
if (!wait)
{
return moveit::core::MoveItErrorCode::SUCCESS;
}
if (!move_action_client_->waitForResult())
{
ROS_INFO_STREAM_NAMED(LOGNAME, "MoveGroup action returned early");
}
if (move_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
{
return move_action_client_->getResult()->error_code;
}
else
{
ROS_INFO_STREAM_NAMED(LOGNAME, move_action_client_->getState().toString()
<< ": " << move_action_client_->getState().getText());
return move_action_client_->getResult()->error_code;
}
}
moveit::core::MoveItErrorCode execute(const moveit_msgs::RobotTrajectory& trajectory, bool wait)
{
if (!execute_action_client_)
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "execute action client not found");
return moveit::core::MoveItErrorCode::FAILURE;
}
if (!execute_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "execute action server not connected");
return moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE;
}
moveit_msgs::ExecuteTrajectoryGoal goal;
goal.trajectory = trajectory;
execute_action_client_->sendGoal(goal);
if (!wait)
{
return moveit::core::MoveItErrorCode::SUCCESS;
}
if (!execute_action_client_->waitForResult())
{
ROS_INFO_STREAM_NAMED(LOGNAME, "ExecuteTrajectory action returned early");
}
if (execute_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
{
return execute_action_client_->getResult()->error_code;
}
else
{
ROS_INFO_STREAM_NAMED(LOGNAME, execute_action_client_->getState().toString()
<< ": " << execute_action_client_->getState().getText());
return execute_action_client_->getResult()->error_code;
}
}
double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double step, double jump_threshold,
moveit_msgs::RobotTrajectory& msg, const moveit_msgs::Constraints& path_constraints,
bool avoid_collisions, moveit_msgs::MoveItErrorCodes& error_code)
{
moveit_msgs::GetCartesianPath::Request req;
moveit_msgs::GetCartesianPath::Response res;
if (considered_start_state_)
moveit::core::robotStateToRobotStateMsg(*considered_start_state_, req.start_state);
else
req.start_state.is_diff = true;
req.group_name = opt_.group_name_;
req.header.frame_id = getPoseReferenceFrame();
req.header.stamp = ros::Time::now();
req.waypoints = waypoints;
req.max_step = step;
req.jump_threshold = jump_threshold;
req.path_constraints = path_constraints;
req.avoid_collisions = avoid_collisions;
req.link_name = getEndEffectorLink();
req.cartesian_speed_limited_link = cartesian_speed_limited_link_;
req.max_cartesian_speed = max_cartesian_speed_;
if (cartesian_path_service_.call(req, res))
{
error_code = res.error_code;
if (res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
{
msg = res.solution;
return res.fraction;
}
else
return -1.0;
}
else
{
error_code.val = error_code.FAILURE;
return -1.0;
}
}
void stop()
{
if (trajectory_event_publisher_)
{
std_msgs::String event;
event.data = "stop";
trajectory_event_publisher_.publish(event);
}
}
bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links)
{
std::string l = link.empty() ? getEndEffectorLink() : link;
if (l.empty())
{
const std::vector<std::string>& links = joint_model_group_->getLinkModelNames();
if (!links.empty())
l = links[0];
}
if (l.empty())