|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
12 #define M_PI (3.14159265358979323846)
21 ok &= m_poly->
view(m_iThreeAxisGyroscopes);
22 ok &= m_poly->view(m_iThreeAxisLinearAccelerometers);
23 ok &= m_poly->view(m_iThreeAxisMagnetometers);
24 ok &= m_poly->view(m_iOrientationSensors);
25 if (m_iThreeAxisGyroscopes) m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename);
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu > m_publisher
virtual bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const =0
Get the last reading of the gyroscope.
#define YARP_LOG_COMPONENT(name,...)
yarp::rosmsg::geometry_msgs::Quaternion orientation
bool view(T *&x)
Get an interface to the device driver.
yarp::rosmsg::geometry_msgs::Vector3 angular_velocity
const size_t m_sens_index
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
yarp::rosmsg::geometry_msgs::Vector3 linear_acceleration
Port & asPort() override
Get the concrete Port being used for communication.
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.
IMURosPublisher: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu...
void run() override
Loop function.
yarp::rosmsg::std_msgs::Header header
virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const =0
Get the last reading of the specified sensor.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
bool isOpen() const
Check if the port has been opened.