YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
realsense2withIMUDriver.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 REALSENSE2IMU_DRIVER_H
10#define REALSENSE2IMU_DRIVER_H
11
13
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
30
32 public realsense2Driver,
36{
37private:
38 typedef yarp::os::Stamp Stamp;
40
41public:
43 ~realsense2withIMUDriver() override = default;
44
45 // DeviceDriver
46 bool open(yarp::os::Searchable& config) override;
47 bool close() override;
48
49private:
50 //method
51 inline bool initializeRealsenseDevice();
52 inline bool setParams();
53
54#if 0
55 bool pipelineStartup(); //inherited
56 bool pipelineShutdown(); //inherited
57 bool pipelineRestart(); //inherited
58 void fallback(); //inherited
59#endif
60
61public:
62 /* IThreeAxisGyroscopes methods */
63 size_t getNrOfThreeAxisGyroscopes() const override;
64 yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override;
65 bool getThreeAxisGyroscopeName(size_t sens_index, std::string& name) const override;
66 bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string& frameName) const override;
67 bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
68
69 /* IThreeAxisLinearAccelerometers methods */
70 size_t getNrOfThreeAxisLinearAccelerometers() const override;
71 yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override;
72 bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string& name) const override;
73 bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string& frameName) const override;
74 bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
75
76 /* IOrientationSensors methods */
77 size_t getNrOfOrientationSensors() const override;
78 yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override;
79 bool getOrientationSensorName(size_t sens_index, std::string& name) const override;
80 bool getOrientationSensorFrameName(size_t sens_index, std::string& frameName) const override;
81 bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const override;
82
83protected:
84 // realsense classes
85 mutable rs2_vector m_last_gyro;
86 mutable rs2_vector m_last_accel;
87 mutable rs2_pose m_last_pose;
89
91
92 //strings
94 const std::string m_accel_sensor_tag = "accelerations_sensor";
95 const std::string m_gyro_sensor_tag = "gyro_sensor";
96 const std::string m_orientation_sensor_tag = "orientation_sensor";
97 const std::string m_position_sensor_tag = "position_sensor";
98 std::string m_gyroFrameName;
99 std::string m_accelFrameName;
102 mutable std::string m_lastError;
103
104 /*std::mutex m_mutex;
105 rs2::context m_ctx;
106 rs2::config m_cfg;
107 rs2::pipeline m_pipeline;
108 rs2::pipeline_profile m_profile;
109 rs2::device m_device;
110 std::vector<rs2::sensor> m_sensors;
111 rs2::sensor* m_depth_sensor;
112 rs2::sensor* m_color_sensor;
113 rs2_intrinsics m_depth_intrin{}, m_color_intrin{}, m_infrared_intrin{};
114 rs2_extrinsics m_depth_to_color{}, m_color_to_depth{};
115 rs2_stream m_alignment_stream{RS2_STREAM_COLOR};
116
117
118 yarp::os::Stamp m_rgb_stamp;
119 yarp::os::Stamp m_depth_stamp;
120 yarp::dev::RGBDSensorParamParser m_paramParser;
121 bool m_verbose;
122 bool m_initialized;
123 bool m_stereoMode;
124 bool m_needAlignment;
125 int m_fps;
126 float m_scale;
127 std::vector<cameraFeature_id_t> m_supportedFeatures;*/
128};
129#endif
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
~realsense2withIMUDriver() override=default
size_t getNrOfOrientationSensors() const override
Get the number of orientation sensors exposed by this device.
size_t getNrOfThreeAxisLinearAccelerometers() const override
Get the number of three axis linear accelerometers exposed by this device.
bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getOrientationSensorName(size_t sens_index, std::string &name) const override
Get the name 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.
bool close() override
Close the DeviceDriver.
bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame 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.
bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
rotation_estimator * m_rotation_estimator
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes exposed by this sensor.
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 getOrientationSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
const std::string m_position_sensor_tag
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
const std::string m_orientation_sensor_tag
yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override
Get the status of the specified sensor.
Device interface to one or multiple orientation sensors, such as IMUs with on board estimation algori...
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.