9#define M_PI (3.14159265358979323846)
18 ok = m_poly->
view(m_iThreeAxisGyroscopes);
23 ok = m_poly->view(m_iThreeAxisLinearAccelerometers);
28 ok = m_poly->view(m_iThreeAxisMagnetometers);
33 ok = m_poly->view(m_iOrientationSensors);
39 ok = m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename);
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu > m_publisher
const size_t m_sens_index
IMURosPublisher: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu...
void run() override
Loop function.
bool view(T *&x)
Get an interface to the device driver.
virtual bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector &rpy, double ×tamp) const =0
Get the last reading of the orientation sensor as roll pitch yaw.
virtual bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const =0
Get the last reading of the gyroscope.
virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const =0
Get the last reading of the specified sensor.
bool isOpen() const
Check if the port has been opened.
Port & asPort() override
Get the concrete Port being used for communication.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
yarp::rosmsg::std_msgs::Header header
yarp::rosmsg::geometry_msgs::Vector3 angular_velocity
yarp::rosmsg::geometry_msgs::Vector3 linear_acceleration
yarp::rosmsg::geometry_msgs::Quaternion orientation
#define yCError(component,...)
#define YARP_LOG_COMPONENT(name,...)