YARP
Yet Another Robot Platform
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 
12 #include <yarp/os/PeriodicThread.h>
13 
14 #include <yarp/dev/DeviceDriver.h>
16 
17 #include "realsense2Driver.h"
18 #include <cstring>
19 #include <iostream>
20 #include <librealsense2/rs.hpp>
21 #include <map>
22 #include <mutex>
23 
24  /**********************************************************************************************************/
25  // This software module is experimental.
26  // It is provided with uncomplete documentation and it may be modified/renamed/removed without any notice.
27  /**********************************************************************************************************/
28 
35 {
36 private:
37  typedef yarp::os::Stamp Stamp;
39 
40 public:
42  ~realsense2Tracking() override = default;
43 
44  // DeviceDriver
45  bool open(yarp::os::Searchable& config) override;
46  bool close() override;
47 
48 private:
49  //method
50  inline bool initializeRealsenseDevice();
51  inline bool setParams();
52 
53  bool pipelineStartup();
54  bool pipelineShutdown();
55  bool pipelineRestart();
56 
57 public:
58  /* IThreeAxisGyroscopes methods */
59  size_t getNrOfThreeAxisGyroscopes() const override;
60  yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override;
61  bool getThreeAxisGyroscopeName(size_t sens_index, std::string& name) const override;
62  bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string& frameName) const override;
63  bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
64 
65  /* IThreeAxisLinearAccelerometers methods */
66  size_t getNrOfThreeAxisLinearAccelerometers() const override;
67  yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override;
68  bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string& name) const override;
69  bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string& frameName) const override;
70  bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
71 
72  /* IOrientationSensors methods */
73  size_t getNrOfOrientationSensors() const override;
74  yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override;
75  bool getOrientationSensorName(size_t sens_index, std::string& name) const override;
76  bool getOrientationSensorFrameName(size_t sens_index, std::string& frameName) const override;
77  bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const override;
78 
79  /* IPositionSensors methods */
80  size_t getNrOfPositionSensors() const override;
81  yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const override;
82  bool getPositionSensorName(size_t sens_index, std::string& name) const override;
83  bool getPositionSensorFrameName(size_t sens_index, std::string& frameName) const override;
84  bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector& xyz, double& timestamp) const override;
85 
86 #if 0
87  /* IPoseSensors methods */
88  size_t getNrOfPoseSensors() const ;
89  yarp::dev::MAS_status getPoseSensorStatus(size_t sens_index) const;
90  bool getPoseSensorName(size_t sens_index, std::string& name) const;
91  bool getPoseSensorFrameName(size_t sens_index, std::string& frameName) const;
92  bool getPoseSensorMeasureAsXYZRPY(size_t sens_index, yarp::sig::Vector& xyzrpy, double& timestamp) const;
93 #endif
94 
95 protected:
96  // realsense classes
97  mutable rs2_vector m_last_gyro;
98  mutable rs2_vector m_last_accel;
99  mutable rs2_pose m_last_pose;
100 
101  //strings
103  const std::string m_accel_sensor_tag = "accelerations_sensor";
104  const std::string m_gyro_sensor_tag = "gyro_sensor";
105  const std::string m_orientation_sensor_tag = "orientation_sensor";
106  const std::string m_position_sensor_tag = "position_sensor";
107  const std::string m_pose_sensor_tag = "pose_sensor";
108  std::string m_gyroFrameName;
109  std::string m_accelFrameName;
111  std::string m_positionFrameName;
112  std::string m_poseFrameName;
113 
114  rs2::config m_cfg;
115  mutable std::mutex m_mutex;
116  rs2::pipeline m_pipeline;
117  rs2::pipeline_profile m_profile;
118  std::string m_lastError;
121 
122  /*
123  rs2::context m_ctx;
124 
125  rs2::device m_device;
126  std::vector<rs2::sensor> m_sensors;
127 
128  bool m_verbose;
129  bool m_initialized;
130  std::vector<cameraFeature_id_t> m_supportedFeatures;*/
131 };
132 #endif
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.
std::string m_orientationFrameName
rs2::pipeline m_pipeline
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.
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.
std::string m_accelFrameName
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.
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.
Definition: DeviceDriver.h:38
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:37
A base class for nested structures that can be searched.
Definition: Searchable.h:69
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.