Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

added magnetic field topic to imu_nws_ros2 #58

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ class GenericSensor_nws_ros2 :
double m_periodInS{0.01};
std::string m_publisherName;
std::string m_rosNodeName;
rclcpp::Node::SharedPtr m_node;
typename rclcpp::Publisher<ROS_MSG>::SharedPtr m_publisher;
yarp::dev::PolyDriver* m_poly;
rclcpp::Node::SharedPtr m_node=nullptr;
typename rclcpp::Publisher<ROS_MSG>::SharedPtr m_publisher=nullptr;
yarp::dev::PolyDriver* m_poly=nullptr;
double m_timestamp;
std::string m_framename;
const size_t m_sens_index = 0;
Expand Down Expand Up @@ -81,9 +81,6 @@ template <class ROS_MSG>
GenericSensor_nws_ros2<ROS_MSG>::GenericSensor_nws_ros2() :
PeriodicThread(0.02)
{
m_node = nullptr;
m_publisher=nullptr;
m_poly = nullptr;
m_timestamp=0;
}

Expand Down Expand Up @@ -188,10 +185,20 @@ bool GenericSensor_nws_ros2<ROS_MSG>::attachAll(const yarp::dev::PolyDriverList

// View all the interfaces
bool ok = viewInterfaces();
if (!ok)
{
yCError(GENERICSENSOR_NWS_ROS2, "viewInterfaces failed.");
return false;
}

// Set rate period
ok &= this->setPeriod(m_periodInS);
ok &= this->start();
if (!ok)
{
yCError(GENERICSENSOR_NWS_ROS2, "thread->start() failed.");
return false;
}

return ok;
}
Expand Down
52 changes: 41 additions & 11 deletions src/devices/multipleAnalogSensors_nws_ros2/Imu_nws_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ YARP_LOG_COMPONENT(GENERICSENSOR_NWS_ROS2, "yarp.device.Imu_nws_ros2")

bool Imu_nws_ros2::viewInterfaces()
{
// View all the interfaces
// View mandatory interfaces
bool ok = true;
ok = m_poly->view(m_iThreeAxisGyroscopes);
if (!ok) {
Expand All @@ -31,19 +31,33 @@ bool Imu_nws_ros2::viewInterfaces()
yCError(GENERICSENSOR_NWS_ROS2) << "IThreeAxisLinearAccelerometers interface is not available";
return false;
}
ok = m_poly->view(m_iThreeAxisMagnetometers);
if (!ok) {
yCError(GENERICSENSOR_NWS_ROS2) << "IThreeAxisMagnetometers interface is not available";
return false;
}
ok = m_poly->view(m_iOrientationSensors);
if (!ok) {
yCError(GENERICSENSOR_NWS_ROS2) << "IOrientationSensors interface is not available";
return false;
}

// View optional interfaces
bool mag_ok = m_poly->view(m_iThreeAxisMagnetometers);
if (mag_ok)
{
std::string m_publisherMagName = m_publisherName + "_magnetic_field";
yCInfo(GENERICSENSOR_NWS_ROS2) << "m_iThreeAxisMagnetometers interface available. Opening topic:" << m_publisherMagName;
m_publisher_mag = m_node->create_publisher<sensor_msgs::msg::MagneticField>(m_publisherMagName,rclcpp::QoS(10));
}
else
{
yCWarning(GENERICSENSOR_NWS_ROS2) << "m_iThreeAxisMagnetometers interface is not available";
}

// Get frame Name
ok = m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename);
return ok;
if (!ok) {
yCError(GENERICSENSOR_NWS_ROS2) << "getThreeAxisGyroscopeFrameName() failed";
return false;
}

return true;
}

void Imu_nws_ros2::run()
Expand All @@ -53,13 +67,16 @@ void Imu_nws_ros2::run()
yarp::sig::Vector vecgyr(3);
yarp::sig::Vector vecacc(3);
yarp::sig::Vector vecrpy(3);

m_iThreeAxisGyroscopes->getThreeAxisGyroscopeMeasure(m_sens_index, vecgyr, m_timestamp);
m_iThreeAxisLinearAccelerometers->getThreeAxisLinearAccelerometerMeasure(m_sens_index, vecacc, m_timestamp);
m_iOrientationSensors->getOrientationSensorMeasureAsRollPitchYaw(m_sens_index, vecrpy, m_timestamp);

tf2::Quaternion quat;
quat.setRPY(vecrpy[0] * M_PI / 180.0, vecrpy[1] * M_PI / 180.0, vecrpy[2] * M_PI / 180.0);
quat.normalize();

sensor_msgs::msg::Imu imu_ros_data;
m_iThreeAxisGyroscopes->getThreeAxisGyroscopeMeasure(m_sens_index, vecgyr, m_timestamp);
m_iThreeAxisLinearAccelerometers->getThreeAxisLinearAccelerometerMeasure(m_sens_index, vecacc, m_timestamp);
m_iOrientationSensors->getOrientationSensorMeasureAsRollPitchYaw(m_sens_index, vecrpy, m_timestamp);
imu_ros_data.header.frame_id = m_framename;
imu_ros_data.header.stamp = ros2TimeFromYarp(m_timestamp);
imu_ros_data.angular_velocity.x = vecgyr[0] * M_PI / 180.0;
Expand All @@ -71,7 +88,20 @@ void Imu_nws_ros2::run()
imu_ros_data.orientation.x = quat.x();
imu_ros_data.orientation.y = quat.y();
imu_ros_data.orientation.z = quat.z();
imu_ros_data.orientation.z = quat.w();
imu_ros_data.orientation.w = quat.w();
m_publisher->publish(imu_ros_data);

if (m_iThreeAxisMagnetometers)
{
yarp::sig::Vector vecmag(3);
m_iThreeAxisMagnetometers->getThreeAxisMagnetometerMeasure(m_sens_index, vecmag, m_timestamp);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Even if the m_iThreeAxisMagnetometers interface exists, it is still possible that getNrOfThreeAxisMagnetometers() returns 0, and this call will return false, so I would either check the return value of getNrOfThreeAxisMagnetometers() and or the return value of this function before putting the data in the message.

sensor_msgs::msg::MagneticField mag_ros_data;
mag_ros_data.header.frame_id = m_framename;
mag_ros_data.header.stamp = ros2TimeFromYarp(m_timestamp);
mag_ros_data.magnetic_field.x=vecmag[0];
mag_ros_data.magnetic_field.y=vecmag[1];
mag_ros_data.magnetic_field.z=vecmag[2];
m_publisher_mag->publish(mag_ros_data);
}
}
}
4 changes: 4 additions & 0 deletions src/devices/multipleAnalogSensors_nws_ros2/Imu_nws_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

#include "GenericSensor_nws_ros2.h"
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/magnetic_field.hpp>

/**
* @ingroup dev_impl_wrapper
Expand Down Expand Up @@ -46,6 +47,9 @@ class Imu_nws_ros2 : public GenericSensor_nws_ros2<sensor_msgs::msg::Imu>

protected:
bool viewInterfaces() override;

private:
rclcpp::Publisher<sensor_msgs::msg::MagneticField>::SharedPtr m_publisher_mag=nullptr;
};

#endif // YARP_DEV_IMU_NWS_ROS2_H
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,12 @@ bool WrenchStamped_nws_ros2::viewInterfaces()
// View all the interfaces
bool ok = m_poly->view(m_iFTsens);
m_iFTsens->getSixAxisForceTorqueSensorFrameName(m_sens_index, m_framename);
return ok;
if (!ok)
{
yCError(GENERICSENSOR_NWS_ROS2) << "getSixAxisForceTorqueSensorFrameName() failed";
return false;
}
return true;
}

void WrenchStamped_nws_ros2::run()
Expand Down