#include <sensor_manager.h>
Definition at line 75 of file sensor_manager.h.
◆ MoveItSensorManager()
moveit_sensor_manager::MoveItSensorManager::MoveItSensorManager |
( |
| ) |
|
|
inline |
◆ ~MoveItSensorManager()
virtual moveit_sensor_manager::MoveItSensorManager::~MoveItSensorManager |
( |
| ) |
|
|
inlinevirtual |
◆ getSensorInfo()
virtual SensorInfo moveit_sensor_manager::MoveItSensorManager::getSensorInfo |
( |
const std::string & |
name | ) |
const |
|
pure virtual |
Get the sensor information for a particular sensor.
◆ getSensorsList()
virtual void moveit_sensor_manager::MoveItSensorManager::getSensorsList |
( |
std::vector< std::string > & |
names | ) |
const |
|
pure virtual |
Get the list of known sensors.
◆ hasSensors()
virtual bool moveit_sensor_manager::MoveItSensorManager::hasSensors |
( |
| ) |
const |
|
pure virtual |
Check if any sensors are known to this manager.
◆ initialize()
virtual bool moveit_sensor_manager::MoveItSensorManager::initialize |
( |
const rclcpp::Node::SharedPtr & |
node | ) |
|
|
pure virtual |
Initialization function for the sensor plugin.
◆ pointSensorTo()
virtual bool moveit_sensor_manager::MoveItSensorManager::pointSensorTo |
( |
const std::string & |
name, |
|
|
const geometry_msgs::msg::PointStamped & |
target, |
|
|
moveit_msgs::msg::RobotTrajectory & |
sensor_trajectory |
|
) |
| |
|
pure virtual |
Point sensor name towards a particular point in space (target). This may require executing a trajectory, but it may or may not execute that trajectory. If it does not, it returns it as part of sensor_trajectory. This is the recommended behaviour, since the caller of this function can perform checks on the safety of the trajectory. The function returns true on success (either completing execution successfully or computing a trajecotory successufully)
The documentation for this class was generated from the following file: