42 #include <moveit_msgs/msg/robot_trajectory.hpp> 
   43 #include <geometry_msgs/msg/point_stamped.hpp> 
   87   virtual bool initialize(
const rclcpp::Node::SharedPtr& node) = 0;
 
  104   virtual bool pointSensorTo(
const std::string& 
name, 
const geometry_msgs::msg::PointStamped& target,
 
  105                              moveit_msgs::msg::RobotTrajectory& sensor_trajectory) = 0;
 
virtual bool hasSensors() const =0
Check if any sensors are known to this manager.
 
virtual bool pointSensorTo(const std::string &name, const geometry_msgs::msg::PointStamped &target, moveit_msgs::msg::RobotTrajectory &sensor_trajectory)=0
 
virtual ~MoveItSensorManager()
 
virtual void getSensorsList(std::vector< std::string > &names) const =0
Get the list of known sensors.
 
virtual bool initialize(const rclcpp::Node::SharedPtr &node)=0
Initialization function for the sensor plugin.
 
virtual SensorInfo getSensorInfo(const std::string &name) const =0
Get the sensor information for a particular sensor.
 
Namespace for the base class of a MoveIt sensor manager.
 
MOVEIT_CLASS_FORWARD(MoveItSensorManager)
 
Define the frame of reference and the frustum of a sensor (usually this is a visual sensor)
 
std::string origin_frame
The name of the frame in which the sensor observation axis is Z and starts at (0,0,...
 
double max_dist
The maximum distance along the Z axis at which observations can be.
 
double x_angle
The range of observations (in radians) on the X axis.
 
double min_dist
The minimum distance along the Z axis at which observations start.
 
double y_angle
The range of observations (in radians) on the Y axis.