14 ok &= m_poly->
view(m_iThreeAxisMagnetometers);
15 m_iThreeAxisMagnetometers->getThreeAxisMagnetometerFrameName(0, m_framename);
26 magfield_ros_data.
clear();
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField > m_publisher
const size_t m_sens_index
MagneticFieldRosPublisher: This wrapper connects to a device and publishes a ROS topic of type sensor...
yarp::dev::IThreeAxisMagnetometers * m_iThreeAxisMagnetometers
void run() override
Loop function.
bool view(T *&x)
Get an interface to the device driver.
virtual bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const =0
Get the last reading of the specified sensor.
yarp::rosmsg::std_msgs::Header header
yarp::rosmsg::geometry_msgs::Vector3 magnetic_field
#define YARP_LOG_COMPONENT(name,...)