moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Simple interface to MoveIt components. More...
Classes | |
class | MoveGroupInterface |
Client class to conveniently use the ROS interfaces provided by the move_group node. More... | |
class | MoveItCppTest |
class | PlanningSceneInterface |
Functions | |
std::shared_ptr< tf2_ros::Buffer > | getSharedTF () |
robot_model_loader::RobotModelLoaderPtr | getSharedRobotModelLoader (const rclcpp::Node::SharedPtr &node, const std::string &robot_description) |
moveit::core::RobotModelConstPtr | getSharedRobotModel (const rclcpp::Node::SharedPtr &node, const std::string &robot_description) |
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 | |
MOVEIT_CLASS_FORWARD (MoveGroupInterface) | |
MOVEIT_CLASS_FORWARD (PlanningSceneInterface) | |
TEST_F (MoveItCppTest, GetCurrentStateTest) | |
TEST_F (MoveItCppTest, NameOfPlanningGroupTest) | |
TEST_F (MoveItCppTest, TestSetStartStateToCurrentState) | |
TEST_F (MoveItCppTest, TestSetGoalFromPoseStamped) | |
TEST_F (MoveItCppTest, TestSetStartStateFromRobotState) | |
TEST_F (MoveItCppTest, TestSetGoalFromRobotState) | |
Variables | |
const std::string | GRASP_PLANNING_SERVICE_NAME = "plan_grasps" |
Simple interface to MoveIt components.
moveit::core::RobotModelConstPtr moveit::planning_interface::getSharedRobotModel | ( | const rclcpp::Node::SharedPtr & | node, |
const std::string & | robot_description | ||
) |
Definition at line 115 of file common_objects.cpp.
robot_model_loader::RobotModelLoaderPtr moveit::planning_interface::getSharedRobotModelLoader | ( | const rclcpp::Node::SharedPtr & | node, |
const std::string & | robot_description | ||
) |
CurrentStateMonitorPtr moveit::planning_interface::getSharedStateMonitor | ( | const rclcpp::Node::SharedPtr & | node, |
const moveit::core::RobotModelConstPtr & | robot_model, | ||
const std::shared_ptr< tf2_ros::Buffer > & | tf_buffer | ||
) |
getSharedStateMonitor
node | A rclcpp::Node::SharePtr to pass node specific configurations, such as callbacks queues. |
robot_model | |
tf_buffer |
Definition at line 132 of file common_objects.cpp.
std::shared_ptr< tf2_ros::Buffer > moveit::planning_interface::getSharedTF | ( | ) |
moveit::planning_interface::MOVEIT_CLASS_FORWARD | ( | MoveGroupInterface | ) |
moveit::planning_interface::MOVEIT_CLASS_FORWARD | ( | PlanningSceneInterface | ) |
moveit::planning_interface::TEST_F | ( | MoveItCppTest | , |
GetCurrentStateTest | |||
) |
Definition at line 102 of file moveit_cpp_test.cpp.
moveit::planning_interface::TEST_F | ( | MoveItCppTest | , |
NameOfPlanningGroupTest | |||
) |
Definition at line 121 of file moveit_cpp_test.cpp.
moveit::planning_interface::TEST_F | ( | MoveItCppTest | , |
TestSetGoalFromPoseStamped | |||
) |
Definition at line 137 of file moveit_cpp_test.cpp.
moveit::planning_interface::TEST_F | ( | MoveItCppTest | , |
TestSetGoalFromRobotState | |||
) |
Definition at line 157 of file moveit_cpp_test.cpp.
moveit::planning_interface::TEST_F | ( | MoveItCppTest | , |
TestSetStartStateFromRobotState | |||
) |
Definition at line 145 of file moveit_cpp_test.cpp.
moveit::planning_interface::TEST_F | ( | MoveItCppTest | , |
TestSetStartStateToCurrentState | |||
) |
Definition at line 127 of file moveit_cpp_test.cpp.
const std::string moveit::planning_interface::GRASP_PLANNING_SERVICE_NAME = "plan_grasps" |
Definition at line 77 of file move_group_interface.cpp.