YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
realsense2Tracking.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3 * All rights reserved.
4 *
5 * This software may be modified and distributed under the terms of the
6 * BSD-3-Clause license. See the accompanying LICENSE file for details.
7 */
8
9#ifndef REALSENSE2TRACKING_H
10#define REALSENSE2TRACKING_H
11
13
17
18#include "realsense2Driver.h"
19#include <cstring>
20#include <iostream>
21#include <librealsense2/rs.hpp>
22#include <map>
23#include <mutex>
24
25 /**********************************************************************************************************/
26 // This software module is experimental.
27 // It is provided with uncomplete documentation and it may be modified/renamed/removed without any notice.
28 /**********************************************************************************************************/
29
37{
38private:
39 typedef yarp::os::Stamp Stamp;
41
42public:
44 ~realsense2Tracking() override = default;
45
46 // DeviceDriver
47 bool open(yarp::os::Searchable& config) override;
48 bool close() override;
49
50private:
51 //method
52 inline bool initializeRealsenseDevice();
53 inline bool setParams();
54
55 bool pipelineStartup();
56 bool pipelineShutdown();
57 bool pipelineRestart();
58
59public:
60 /* IThreeAxisGyroscopes methods */
61 size_t getNrOfThreeAxisGyroscopes() const override;
62 yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override;
63 bool getThreeAxisGyroscopeName(size_t sens_index, std::string& name) const override;
64 bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string& frameName) const override;
65 bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
66
67 /* IThreeAxisLinearAccelerometers methods */
68 size_t getNrOfThreeAxisLinearAccelerometers() const override;
69 yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override;
70 bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string& name) const override;
71 bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string& frameName) const override;
72 bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
73
74 /* IOrientationSensors methods */
75 size_t getNrOfOrientationSensors() const override;
76 yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override;
77 bool getOrientationSensorName(size_t sens_index, std::string& name) const override;
78 bool getOrientationSensorFrameName(size_t sens_index, std::string& frameName) const override;
79 bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const override;
80
81 /* IPositionSensors methods */
82 size_t getNrOfPositionSensors() const override;
83 yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const override;
84 bool getPositionSensorName(size_t sens_index, std::string& name) const override;
85 bool getPositionSensorFrameName(size_t sens_index, std::string& frameName) const override;
86 bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector& xyz, double& timestamp) const override;
87
88 /* IAnalogSensor methods */
89 int read(yarp::sig::Vector &out) override;
90 int getState(int ch) override;
91 int getChannels() override;
92 int calibrateSensor() override;
93 int calibrateSensor(const yarp::sig::Vector& value) override;
94 int calibrateChannel(int ch) override;
95 int calibrateChannel(int ch, double value) override;
96
97#if 0
98 /* IPoseSensors methods */
99 size_t getNrOfPoseSensors() const ;
100 yarp::dev::MAS_status getPoseSensorStatus(size_t sens_index) const;
101 bool getPoseSensorName(size_t sens_index, std::string& name) const;
102 bool getPoseSensorFrameName(size_t sens_index, std::string& frameName) const;
103 bool getPoseSensorMeasureAsXYZRPY(size_t sens_index, yarp::sig::Vector& xyzrpy, double& timestamp) const;
104#endif
105
106protected:
107 // realsense classes
108 mutable rs2_vector m_last_gyro;
109 mutable rs2_vector m_last_accel;
110 mutable rs2_pose m_last_pose;
111
112 //strings
114 const std::string m_accel_sensor_tag = "accelerations_sensor";
115 const std::string m_gyro_sensor_tag = "gyro_sensor";
116 const std::string m_orientation_sensor_tag = "orientation_sensor";
117 const std::string m_position_sensor_tag = "position_sensor";
118 const std::string m_pose_sensor_tag = "pose_sensor";
119 std::string m_gyroFrameName;
120 std::string m_accelFrameName;
123 std::string m_poseFrameName;
124
125 rs2::config m_cfg;
126 mutable std::mutex m_mutex;
127 rs2::pipeline m_pipeline;
128 rs2::pipeline_profile m_profile;
129 mutable std::string m_lastError;
132
133 /*
134 rs2::context m_ctx;
135
136 rs2::device m_device;
137 std::vector<rs2::sensor> m_sensors;
138
139 bool m_verbose;
140 bool m_initialized;
141 std::vector<cameraFeature_id_t> m_supportedFeatures;*/
142};
143#endif
analog sensor interface
const std::string m_position_sensor_tag
yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override
Get the status of the specified sensor.
int read(yarp::sig::Vector &out) override
Read a vector from the sensor.
std::string m_orientationFrameName
timestamp_enumtype m_timestamp_type
bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
size_t getNrOfPositionSensors() const override
Get the number of position sensors exposed by this device.
int getChannels() override
Get the number of channels of the sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getPositionSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
const std::string m_accel_sensor_tag
size_t getNrOfThreeAxisLinearAccelerometers() const override
Get the number of three axis linear accelerometers exposed by this device.
size_t getNrOfOrientationSensors() const override
Get the number of orientation sensors exposed by this device.
yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
const std::string m_pose_sensor_tag
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
std::string m_inertial_sensor_name_prefix
const std::string m_gyro_sensor_tag
bool close() override
Close the DeviceDriver.
const std::string m_orientation_sensor_tag
bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double &timestamp) const override
Get the last reading of the position sensor as x y z.
bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
std::string m_positionFrameName
bool getPositionSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
~realsense2Tracking() override=default
rs2::pipeline_profile m_profile
bool getOrientationSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
int calibrateSensor() override
Calibrates the whole sensor.
int calibrateChannel(int ch) override
Calibrates one single channel.
bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector &rpy, double &timestamp) const override
Get the last reading of the orientation sensor as roll pitch yaw.
yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the gyroscope.
int getState(int ch) override
Check the state value of a given channel.
yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes exposed by this sensor.
Interface implemented by all device drivers.
A generic interface to sensors (gyro, a/d converters).
Device interface to one or multiple orientation sensors, such as IMUs with on board estimation algori...
Device interface to one or multiple position sensors, such as UWB localization sensors.
Device interface to one or multiple three axis gyroscopes.
Device interface to one or multiple three axis linear accelerometers.
A class for storing options and configuration information.
Definition Property.h:33
A base class for nested structures that can be searched.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.