moveit2
The MoveIt Motion Planning Framework for ROS 2.
Namespaces | Functions
common_objects.h File Reference
#include <memory>
#include <tf2_ros/buffer.h>
#include <moveit/planning_scene_monitor/current_state_monitor.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
Include dependency graph for common_objects.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 moveit
 Main namespace for MoveIt.
 
 moveit::planning_interface
 Simple interface to MoveIt components.
 

Functions

std::shared_ptr< tf2_ros::Buffer > moveit::planning_interface::getSharedTF ()
 
robot_model_loader::RobotModelLoaderPtr moveit::planning_interface::getSharedRobotModelLoader (const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
 
moveit::core::RobotModelConstPtr moveit::planning_interface::getSharedRobotModel (const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
 
planning_scene_monitor::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 More...