moveit2
The MoveIt Motion Planning Framework for ROS 2.
sensor_manager.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <vector>
40 #include <string>
42 #include <moveit_msgs/msg/robot_trajectory.hpp>
43 #include <geometry_msgs/msg/point_stamped.hpp>
44 
47 {
49 struct SensorInfo
50 {
51  SensorInfo() : min_dist(0.), max_dist(0.0), x_angle(0.0), y_angle(0.0)
52  {
53  }
54 
56  std::string origin_frame;
57 
58  /* Define the frustum (or approximation of the frustum) */
59 
61  double min_dist;
62 
64  double max_dist;
65 
67  double x_angle;
68 
70  double y_angle;
71 };
72 
73 MOVEIT_CLASS_FORWARD(MoveItSensorManager); // Defines MoveItSensorManagerPtr, ConstPtr, WeakPtr... etc
74 
76 {
77 public:
79  {
80  }
81 
83  {
84  }
85 
87  virtual bool initialize(const rclcpp::Node::SharedPtr& node) = 0;
88 
90  virtual void getSensorsList(std::vector<std::string>& names) const = 0;
91 
93  virtual SensorInfo getSensorInfo(const std::string& name) const = 0;
94 
96  virtual bool hasSensors() const = 0;
97 
104  virtual bool pointSensorTo(const std::string& name, const geometry_msgs::msg::PointStamped& target,
105  moveit_msgs::msg::RobotTrajectory& sensor_trajectory) = 0;
106 };
107 } // namespace moveit_sensor_manager
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 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)
name
Definition: setup.py:7
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.