moveit_cpp.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik LLC
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 PickNik LLC 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: Henning Kayser
36  Desc: A high level interface that does not require the use of ROS Actions, Services, and Messages to access the
37  core MoveIt functionality
38 */
39 
40 #pragma once
41 
42 #include <ros/ros.h>
47 #include <tf2_ros/buffer.h>
49 
50 namespace moveit_cpp
51 {
52 MOVEIT_CLASS_FORWARD(MoveItCpp); // Defines MoveItCppPtr, ConstPtr, WeakPtr... etc
53 
54 class MoveItCpp
55 {
56 public:
58  struct PlanningSceneMonitorOptions
59  {
60  void load(const ros::NodeHandle& nh)
61  {
62  std::string ns = "planning_scene_monitor_options/";
63  nh.param<std::string>(ns + "name", name, "planning_scene_monitor");
64  nh.param<std::string>(ns + "robot_description", robot_description, "robot_description");
65  nh.param(ns + "joint_state_topic", joint_state_topic,
67  nh.param(ns + "attached_collision_object_topic", attached_collision_object_topic,
69  nh.param(ns + "monitored_planning_scene_topic", monitored_planning_scene_topic,
71  nh.param(ns + "publish_planning_scene_topic", publish_planning_scene_topic,
73  nh.param<double>(ns + "wait_for_initial_state_timeout", wait_for_initial_state_timeout, 0.0);
74  }
75  std::string name;
76  std::string robot_description;
77  std::string joint_state_topic;
80  std::string publish_planning_scene_topic;
82  };
83 
85  struct PlanningPipelineOptions
86  {
87  void load(const ros::NodeHandle& nh)
88  {
89  std::string ns = "planning_pipelines/";
90  nh.getParam(ns + "pipeline_names", pipeline_names);
91  nh.getParam(ns + "namespace", parent_namespace);
92  }
93  std::vector<std::string> pipeline_names;
94  std::string parent_namespace;
95  };
96 
98  struct Options
99  {
100  Options(const ros::NodeHandle& nh)
101  {
104  }
105 
106  PlanningSceneMonitorOptions planning_scene_monitor_options;
108  };
109 
111  MoveItCpp(const ros::NodeHandle& nh, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = {});
112  MoveItCpp(const Options& options, const ros::NodeHandle& nh, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = {});
113 
119  MoveItCpp(const MoveItCpp&) = delete;
120  MoveItCpp& operator=(const MoveItCpp&) = delete;
121 
122  MoveItCpp(MoveItCpp&& other) = default;
123  MoveItCpp& operator=(MoveItCpp&& other) = default;
124 
127 
129  moveit::core::RobotModelConstPtr getRobotModel() const;
130 
133 
136  bool getCurrentState(moveit::core::RobotStatePtr& current_state, double wait_seconds);
137 
140  moveit::core::RobotStatePtr getCurrentState(double wait_seconds = 0.0);
141 
143  const std::map<std::string, planning_pipeline::PlanningPipelinePtr>& getPlanningPipelines() const;
144 
146  planning_scene_monitor::PlanningSceneMonitorConstPtr getPlanningSceneMonitor() const;
147  planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst();
148 
149  std::shared_ptr<const tf2_ros::Buffer> getTFBuffer() const;
150  std::shared_ptr<tf2_ros::Buffer> getTFBuffer();
151 
153  trajectory_execution_manager::TrajectoryExecutionManagerConstPtr getTrajectoryExecutionManager() const;
154  trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst();
155 
158  bool execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
159  bool blocking = true);
160 
162  bool terminatePlanningPipeline(std::string const& pipeline_name);
163 
164 protected:
165  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
166  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
167 
168 private:
169  // Core properties and instances
171  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
172 
173  // Planning
174  std::map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines_;
175  std::map<std::string, std::set<std::string>> groups_algorithms_map_;
176 
177  // Execution
178  trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
179 
182 
184  bool loadPlanningPipelines(const PlanningPipelineOptions& options);
185 };
186 } // namespace moveit_cpp
187 
188 namespace moveit
189 {
191 {
192 using MoveItCpp [[deprecated("use moveit_cpp")]] = moveit_cpp::MoveItCpp;
193 [[deprecated("use moveit_cpp")]] MOVEIT_DECLARE_PTR(MoveItCpp, moveit_cpp::MoveItCpp);
194 } // namespace planning_interface
195 } // namespace moveit
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::publish_planning_scene_topic
std::string publish_planning_scene_topic
Definition: moveit_cpp.h:112
moveit_cpp::MoveItCpp::getPlanningSceneMonitor
planning_scene_monitor::PlanningSceneMonitorConstPtr getPlanningSceneMonitor() const
Get the stored instance of the planning scene monitor.
Definition: moveit_cpp.cpp:238
moveit_cpp::MoveItCpp::execute
bool execute(const std::string &group_name, const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, bool blocking=true)
Execute a trajectory on the planning group specified by group_name using the trajectory execution man...
Definition: moveit_cpp.cpp:258
moveit_cpp::MoveItCpp::Options
Parameter container for initializing MoveItCpp.
Definition: moveit_cpp.h:130
moveit_cpp::MoveItCpp::trajectory_execution_manager_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
Definition: moveit_cpp.h:210
moveit_cpp::MoveItCpp::Options::Options
Options(const ros::NodeHandle &nh)
Definition: moveit_cpp.h:132
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::joint_state_topic
std::string joint_state_topic
Definition: moveit_cpp.h:109
moveit_cpp::MoveItCpp::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: moveit_cpp.h:203
moveit_cpp::MoveItCpp::~MoveItCpp
~MoveItCpp()
Destructor.
Definition: moveit_cpp.cpp:121
moveit_cpp::MoveItCpp::MoveItCpp
MoveItCpp(const ros::NodeHandle &nh, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer={})
Constructor.
Definition: moveit_cpp.cpp:77
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
buffer.h
moveit_cpp::MoveItCpp::terminatePlanningPipeline
bool terminatePlanningPipeline(std::string const &pipeline_name)
Utility to terminate a given planning pipeline.
Definition: moveit_cpp.cpp:288
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::monitored_planning_scene_topic
std::string monitored_planning_scene_topic
Definition: moveit_cpp.h:111
moveit_cpp::MoveItCpp::planning_pipelines_
std::map< std::string, planning_pipeline::PlanningPipelinePtr > planning_pipelines_
Definition: moveit_cpp.h:206
robot_state.h
moveit_cpp::MoveItCpp
Definition: moveit_cpp.h:86
moveit_cpp::MoveItCpp::operator=
MoveItCpp & operator=(const MoveItCpp &)=delete
moveit_cpp
Definition: moveit_cpp.h:50
moveit_cpp::MoveItCpp::getRobotModel
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
Definition: moveit_cpp.cpp:201
robot_trajectory
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::robot_description
std::string robot_description
Definition: moveit_cpp.h:108
moveit_cpp::MoveItCpp::PlanningPipelineOptions::pipeline_names
std::vector< std::string > pipeline_names
Definition: moveit_cpp.h:125
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions
Specification of options to use when constructing the MoveItCpp class.
Definition: moveit_cpp.h:90
moveit_cpp::MoveItCpp::getTrajectoryExecutionManagerNonConst
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst()
Definition: moveit_cpp.cpp:253
moveit_cpp::MoveItCpp::getTFBuffer
std::shared_ptr< const tf2_ros::Buffer > getTFBuffer() const
Definition: moveit_cpp.cpp:307
moveit_cpp::MoveItCpp::PlanningPipelineOptions::load
void load(const ros::NodeHandle &nh)
Definition: moveit_cpp.h:119
moveit_cpp::MoveItCpp::getCurrentState
bool getCurrentState(moveit::core::RobotStatePtr &current_state, double wait_seconds)
Get the current state queried from the current state monitor.
Definition: moveit_cpp.cpp:211
moveit::planning_interface::MOVEIT_DECLARE_PTR
MOVEIT_DECLARE_PTR(MoveItCpp, moveit_cpp::MoveItCpp)
planning_scene_monitor.h
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::attached_collision_object_topic
std::string attached_collision_object_topic
Definition: moveit_cpp.h:110
moveit_cpp::MoveItCpp::getPlanningSceneMonitorNonConst
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst()
Definition: moveit_cpp.cpp:243
moveit_cpp::MoveItCpp::PlanningPipelineOptions
struct contains the the variables used for loading the planning pipeline
Definition: moveit_cpp.h:117
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::wait_for_initial_state_timeout
double wait_for_initial_state_timeout
Definition: moveit_cpp.h:113
moveit_cpp::MoveItCpp::getNodeHandle
const ros::NodeHandle & getNodeHandle() const
Get the ROS node handle of this instance operates on.
Definition: moveit_cpp.cpp:206
moveit_cpp::MoveItCpp::node_handle_
ros::NodeHandle node_handle_
Definition: moveit_cpp.h:202
moveit_cpp::MoveItCpp::getTrajectoryExecutionManager
trajectory_execution_manager::TrajectoryExecutionManagerConstPtr getTrajectoryExecutionManager() const
Get the stored instance of the trajectory execution manager.
Definition: moveit_cpp.cpp:248
moveit_cpp::MoveItCpp::Options::planning_pipeline_options
PlanningPipelineOptions planning_pipeline_options
Definition: moveit_cpp.h:139
moveit_cpp::MoveItCpp::groups_algorithms_map_
std::map< std::string, std::set< std::string > > groups_algorithms_map_
Definition: moveit_cpp.h:207
moveit_cpp::MoveItCpp::getPlanningPipelines
const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines() const
Get all loaded planning pipeline instances mapped to their reference names.
Definition: moveit_cpp.cpp:233
transform_listener.h
moveit_cpp::MoveItCpp::tf_listener_
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
Definition: moveit_cpp.h:198
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
Definition: planning_scene_monitor.h:116
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
Definition: planning_scene_monitor.h:129
moveit_cpp::MoveItCpp::loadPlanningSceneMonitor
bool loadPlanningSceneMonitor(const PlanningSceneMonitorOptions &options)
Initialize and setup the planning scene monitor.
Definition: moveit_cpp.cpp:126
planning_scene_monitor::PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC
static const std::string MONITORED_PLANNING_SCENE_TOPIC
Definition: planning_scene_monitor.h:136
moveit
trajectory_execution_manager.h
planning_pipeline.h
planning_interface
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::load
void load(const ros::NodeHandle &nh)
Definition: moveit_cpp.h:92
moveit_cpp::MoveItCpp::PlanningPipelineOptions::parent_namespace
std::string parent_namespace
Definition: moveit_cpp.h:126
moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::name
std::string name
Definition: moveit_cpp.h:107
moveit_cpp::MoveItCpp::Options::planning_scene_monitor_options
PlanningSceneMonitorOptions planning_scene_monitor_options
Definition: moveit_cpp.h:138
moveit_cpp::MoveItCpp::loadPlanningPipelines
bool loadPlanningPipelines(const PlanningPipelineOptions &options)
Initialize and setup the planning pipelines.
Definition: moveit_cpp.cpp:162
moveit_cpp::MoveItCpp::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: moveit_cpp.h:197
ros::NodeHandle
moveit::planning_interface::MoveItCpp
moveit_cpp::MoveItCpp MoveItCpp
Definition: moveit_cpp.h:192
moveit_cpp::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(MoveItCpp)
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
Definition: planning_scene_monitor.h:119


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19