23#include <librealsense2/rsutil.h>
24#include <librealsense2/rs.hpp>
50 return {
x * t,
y * t,
z * t };
55 return {
x - t,
y - t,
z - t };
65 void add(
float t1,
float t2,
float t3)
83 double last_ts_gyro = 0;
102 double dt_gyro = (ts - last_ts_gyro) / 1000.0;
109 std::lock_guard<std::mutex> lock(theta_mtx);
124 std::lock_guard<std::mutex> lock(theta_mtx);
148 std::lock_guard<std::mutex> lock(theta_mtx);
159 std::stringstream
ss;
160 ss <<
"Device information: " << std::endl;
164 ss <<
" " << std::left << std::setw(20) <<
info_type <<
" : ";
169 ss <<
"N/A" << std::endl;
190 }
catch (
const rs2::error&
e) {
214 }
catch (
const rs2::error&
e) {
241 }
catch (
const rs2::error&
e) {
243 <<
"(" <<
e.what() <<
")";
254 }
catch (
const rs2::error&
e) {
256 <<
"(" <<
e.what() <<
")";
286 yCWarning(
REALSENSE2WITHIMU) <<
"It is provided with uncomplete documentation and it may be modified/renamed/removed without any notice.";
373 catch (
const rs2::error&
e)
380 rs2::motion_frame
gyro =
fg.as<rs2::motion_frame>();
425 catch (
const rs2::error&
e)
432 rs2::motion_frame
accel =
fa.as<rs2::motion_frame>();
491 catch (
const rs2::error&
e)
502 double ts =
motion.get_timestamp();
519 rpy[0] = 0 + theta.
x * 180.0 /
M_PI;
520 rpy[1] = 0 + theta.
y * 180.0 /
M_PI;
521 rpy[2] = 0 + theta.
z * 180.0 /
M_PI;
rs2_intrinsics m_color_intrin
rs2::pipeline_profile m_profile
rs2_intrinsics m_depth_intrin
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const override
Get the last reading of the specified sensor.
realsense2withIMUDriver()
size_t getNrOfOrientationSensors() const override
Get the number of orientation sensors exposed by this device.
bool m_sensor_has_orientation_estimator
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.
std::string m_accelFrameName
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.
const std::string m_accel_sensor_tag
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) 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.
const std::string m_gyro_sensor_tag
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 ×tamp) const override
Get the last reading of the orientation sensor as roll pitch yaw.
std::string m_gyroFrameName
std::string m_inertial_sensor_name_prefix
yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
std::string m_orientationFrameName
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.
void process_gyro(rs2_vector gyro_data, double ts)
void process_accel(rs2_vector accel_data)
A mini-server for performing network communication in the background.
A base class for nested structures that can be searched.
void resize(size_t size) override
Resize the vector.
#define yCError(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.
@ MAS_UNKNOWN
The sensor is in an unknown state.
@ MAS_OK
The sensor is working correctly.
An interface to the operating system, including Port based communication.
static bool setOption(rs2_option option, const rs2::sensor *sensor, float value)
static bool getOption(rs2_option option, const rs2::sensor *sensor, float &value)
static std::string get_device_information(const rs2::device &dev)
static void settingErrorMsg(const string &error, bool &ret)
float3 operator-(float t)
void add(float t1, float t2, float t3)
float3 operator*(float t)