|
Studica - Roscpp Documentation
VMX-pi ROS Library
|
#include <navX_ros_wrapper.h>
Public Member Functions | |
| navXROSWrapper (ros::NodeHandle *nh, VMXPi *vmx) | |
| Constructs the NavX object using the specified parameters. More... | |
| ~navXROSWrapper () | |
| Destructor for the NavX object. More... | |
| bool | GetFirmwareVersion (vmxpi_ros::StringRes::Request &req, vmxpi_ros::StringRes::Response &res) |
| Provides the ROS service to get the firmware version number currently executing on the NavX when this service is called on the get_ahrs_firmware_version server. More... | |
| void | PubRollPitchYaw () |
| Provides a grouped publisher for roll, pitch, and yaw (-180 to 180 deg) to the navx/roll_pitch_yaw topic. More... | |
| void | PubPitch () |
| Publishes the pitch readings from the NavX sensor to the navx/pitch topic. More... | |
| void | PubRoll () |
| Publishes the roll readings from the NavX sensor to the navx/roll topic. More... | |
| void | PubYaw () |
| Publishes the yaw readings (in degrees, from -180 to 180) from the NavX sensor to the navx/yaw topic. More... | |
| void | PubAngle () |
| Publishes the continuous angle readings from the NavX sensor to the navx/pitch topic. More... | |
| void | PubHeading () |
| Publishes the compass heading readings from the NavX sensor to the navx/heading topic. More... | |
| void | PubLinearAccel () |
| Provides a grouped publisher for the linear acceleration in the X,Y, and Z axes to the navx/linear_accel topic. More... | |
| void | PubLinAccelX () |
| Publishes the world linear acceleration in the X-axis (in G) to the navx/linear_accel/x. More... | |
| void | PubLinAccelY () |
| Publishes the world linear acceleration in the Y-axis (in G) to the navx/linear_accel/y. More... | |
| void | PubLinAccelZ () |
| Publishes the world linear acceleration in the Z-axis (in G) to the navx/linear_accel/z. More... | |
| void | PubFusedHeading () |
| Publishes the fused (9-axis) heading in degrees (range 0-360) to the navx/fused_heading. This is the fusion of the yaw angle, the tilt corrected compass heading, and magnetic disturbance detection. More... | |
| void | PubTimestamp () |
| Publishes the timestamp of the last sensor message reported from the NavX to the navx/last_sensor_timestamp. More... | |
| void | PubQuaternion () |
| Provides a grouped publisher for the orientation quaternion axes (W, X, Y, Z) with respect to where the yaw angle was last "zeroed" to the navx/quaternion. More... | |
| void | PubQuatX () |
| Publishes the real portion (X-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/x. More... | |
| void | PubQuatY () |
| Publishes the real portion (X-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/y. More... | |
| void | PubQuatZ () |
| Publishes the real portion (X-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/z. More... | |
| void | PubQuatW () |
| Publishes the imaginary portion (W-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/w. More... | |
| void | PubVelocity () |
| Provides a grouped publisher for velocity (in meters/sec) in the X, Y, and Z axes to the navx/velocity topic. More... | |
| void | PubVelX () |
| Publishes the velocity (in meters/sec) in the X-axis to the navx/velocity/x. More... | |
| void | PubVelY () |
| Publishes the velocity (in meters/sec) in the Y-axis to the navx/velocity/y. More... | |
| void | PubVelZ () |
| Publishes the velocity (in meters/sec) in the Z-axis to the navx/velocity/z. More... | |
| void | PubDisplacement () |
| Provides a grouped publisher for displacement (in meters) in the X, Y, and Z axes since reset_displacement service is called to the navx/displacement topic. More... | |
| void | PubDisplaceX () |
| Publishes the displacement (in meters) in the X-axis to the navx/displacement/x topic since the reset_displacement service was last called. More... | |
| void | PubDisplaceY () |
| Publishes the displacement (in meters) in the Y-axis to the navx/displacement/y topic since the reset_displacement service was last called. More... | |
| void | PubDisplaceZ () |
| Publishes the displacement (in meters) in the Z-axis to the navx/displacement/z topic since the reset_displacement service was last called. More... | |
| void | PubRawGyro () |
| Provides a grouped publisher for the gyro rotation rate (in degrees/sec) in the X, Y, and Z axes to the navx/raw_gyro topic. More... | |
| void | PubRawGyroX () |
| Publishes the raw gyro rotation rate (in degrees/sec) in the X-axis to the navx/raw_gyro/x topic. More... | |
| void | PubRawGyroY () |
| Publishes the raw gyro rotation rate (in degrees/sec) in the Y-axis to the navx/raw_gyro/y topic. More... | |
| void | PubRawGyroZ () |
| Publishes the raw gyro rotation rate (in degrees/sec) in the X-axis to the navx/raw_gyro/z topic. More... | |
| void | PubRawAccel () |
| Provides a grouped publisher for the raw acceleration rate (G) in the X, Y, and Z axes to the navx/raw_accel topic. More... | |
| void | PubRawAccelX () |
| Publishes the raw acceleration rate (G) in the X-axis to the navx/raw_accel/x topic. More... | |
| void | PubRawAccelY () |
| Publishes the raw acceleration rate (G) in the Y-axis to the navx/raw_accel/y topic. More... | |
| void | PubRawAccelZ () |
| Publishes the raw acceleration rate (G) in the Z-axis to the navx/raw_accel/z topic. More... | |
| void | PubRawMag () |
| Provides a grouped publishers to for the raw magnetometer readings (in µTesla) in the X, Y, and Z axes to the navx/raw_mag topic. More... | |
| void | PubRawMagX () |
| Publishes the raw magnetometer readings (in µTesla) in the X-axis to the navx/raw_mag/x topic. More... | |
| void | PubRawMagY () |
| Publishes the raw magnetometer readings (in µTesla) in the Y-axis to the navx/raw_mag/y topic. More... | |
| void | PubRawMagZ () |
| Publishes the raw magnetometer readings (in µTesla) in the Z-axis to the navx/raw_mag/z topic. More... | |
| void | PubPose () |
| bool | GetUpdateRate (vmxpi_ros::IntRes::Request &req, vmxpi_ros::IntRes::Response &res) |
| Provides the ROS service to access the update rate of the NavX. More... | |
| bool | Reset (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| Provides the ROS service to zero the yaw angle. More... | |
| bool | ResetDisplacement (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| Provides the ROS service to reset the displacement, meaning a new origin is set where this is invoked. More... | |
| bool | IsCalibrating () |
| Returns TRUE if the NavX is currently performing gyro/accelerometer calibration. More... | |
| bool | IsConnected () |
| Signifies whether the sensor is connected to the host computer. More... | |
| bool | IsMoving () |
| Signifies whether the NavX is detecting motion based on the X and Y-axis world linear acceleration values. More... | |
| bool | IsRotating () |
| Signifies whether the NavX is detecting motion about the Z-axis (yaw rotation). More... | |
| bool | IsMagnDisturbance () |
| Signifies whether the value of the calibrated magnetic field strength for earth's magnetic field differs from the current magnetic field strength. More... | |
| bool | IsMagCalibrated () |
| Signifies whether the magnetometer has been calibrated, this is done by the user. More... | |
| void | Run_t () |
| Provides a method to call a thread of various Publishers of the NaxXROS library advertising sensor data to the ROS Master node. More... | |
| navXROSWrapper::navXROSWrapper | ( | ros::NodeHandle * | nh, |
| VMXPi * | vmx | ||
| ) |
Constructs the NavX object using the specified parameters.
| nh | Internal reference to the ROS node that the program will use to interact with the ROS system. |
| vmx | VMX-pi parameter used to initialize the VMX-pi HAL. |
| navXROSWrapper::~navXROSWrapper | ( | ) |
Destructor for the NavX object.
| bool navXROSWrapper::GetFirmwareVersion | ( | vmxpi_ros::StringRes::Request & | req, |
| vmxpi_ros::StringRes::Response & | res | ||
| ) |
Provides the ROS service to get the firmware version number currently executing on the NavX when this service is called on the get_ahrs_firmware_version server.
| req | Request service type defined in the StringRes.srv file. |
| res | Response service type defined in the StringRes.srv file. |
| bool navXROSWrapper::GetUpdateRate | ( | vmxpi_ros::IntRes::Request & | req, |
| vmxpi_ros::IntRes::Response & | res | ||
| ) |
Provides the ROS service to access the update rate of the NavX.
| req | Request service type defined in the IntRes.srv file. |
| res | Response service type defined in the IntRes.srv file. |
| bool navXROSWrapper::IsCalibrating | ( | ) |
Returns TRUE if the NavX is currently performing gyro/accelerometer calibration.
NOTE: Automatic calibration takes place when the NavX is initially powered on, ensure the sensor is completely still with the Z-axis perpendicular to the earth.
| bool navXROSWrapper::IsConnected | ( | ) |
Signifies whether the sensor is connected to the host computer.
| bool navXROSWrapper::IsMagCalibrated | ( | ) |
Signifies whether the magnetometer has been calibrated, this is done by the user.
| bool navXROSWrapper::IsMagnDisturbance | ( | ) |
Signifies whether the value of the calibrated magnetic field strength for earth's magnetic field differs from the current magnetic field strength.
| bool navXROSWrapper::IsMoving | ( | ) |
Signifies whether the NavX is detecting motion based on the X and Y-axis world linear acceleration values.
| bool navXROSWrapper::IsRotating | ( | ) |
Signifies whether the NavX is detecting motion about the Z-axis (yaw rotation).
| void navXROSWrapper::PubAngle | ( | ) |
Publishes the continuous angle readings from the NavX sensor to the navx/pitch topic.
NOTE: This value is the total accumulated yaw angle, in other words its range is beyond 360 degrees.
| void navXROSWrapper::PubDisplacement | ( | ) |
Provides a grouped publisher for displacement (in meters) in the X, Y, and Z axes since reset_displacement service is called to the navx/displacement topic.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as displacement measurements depend on the double-integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting displacement are not known to be accurate.
| void navXROSWrapper::PubDisplaceX | ( | ) |
Publishes the displacement (in meters) in the X-axis to the navx/displacement/x topic since the reset_displacement service was last called.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as displacement measurements depend on the double-integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting displacement are not known to be accurate.
| void navXROSWrapper::PubDisplaceY | ( | ) |
Publishes the displacement (in meters) in the Y-axis to the navx/displacement/y topic since the reset_displacement service was last called.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as displacement measurements depend on the double-integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting displacement are not known to be accurate.
| void navXROSWrapper::PubDisplaceZ | ( | ) |
Publishes the displacement (in meters) in the Z-axis to the navx/displacement/z topic since the reset_displacement service was last called.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as displacement measurements depend on the double-integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting displacement are not known to be accurate.
| void navXROSWrapper::PubFusedHeading | ( | ) |
Publishes the fused (9-axis) heading in degrees (range 0-360) to the navx/fused_heading. This is the fusion of the yaw angle, the tilt corrected compass heading, and magnetic disturbance detection.
NOTE: Magnetometer calibration is required.
| void navXROSWrapper::PubHeading | ( | ) |
Publishes the compass heading readings from the NavX sensor to the navx/heading topic.
| void navXROSWrapper::PubLinAccelX | ( | ) |
Publishes the world linear acceleration in the X-axis (in G) to the navx/linear_accel/x.
| void navXROSWrapper::PubLinAccelY | ( | ) |
Publishes the world linear acceleration in the Y-axis (in G) to the navx/linear_accel/y.
| void navXROSWrapper::PubLinAccelZ | ( | ) |
Publishes the world linear acceleration in the Z-axis (in G) to the navx/linear_accel/z.
| void navXROSWrapper::PubLinearAccel | ( | ) |
Provides a grouped publisher for the linear acceleration in the X,Y, and Z axes to the navx/linear_accel topic.
| void navXROSWrapper::PubPitch | ( | ) |
Publishes the pitch readings from the NavX sensor to the navx/pitch topic.
| void navXROSWrapper::PubPose | ( | ) |
Publishes the pose message, which is the combination of position and orientation data. The point position messages are composed using the GetDisplacement*() accessors while the orientation messages are loaded using the GetQuaternion*() accessors from the VMX-pi HAL.
| void navXROSWrapper::PubQuaternion | ( | ) |
Provides a grouped publisher for the orientation quaternion axes (W, X, Y, Z) with respect to where the yaw angle was last "zeroed" to the navx/quaternion.
| void navXROSWrapper::PubQuatW | ( | ) |
Publishes the imaginary portion (W-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/w.
| void navXROSWrapper::PubQuatX | ( | ) |
Publishes the real portion (X-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/x.
| void navXROSWrapper::PubQuatY | ( | ) |
Publishes the real portion (X-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/y.
| void navXROSWrapper::PubQuatZ | ( | ) |
Publishes the real portion (X-axis) of the orientation quaternion with respect to where the yaw angle was last "zeroed" to the navx/quaternion/z.
| void navXROSWrapper::PubRawAccel | ( | ) |
Provides a grouped publisher for the raw acceleration rate (G) in the X, Y, and Z axes to the navx/raw_accel topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawAccelX | ( | ) |
Publishes the raw acceleration rate (G) in the X-axis to the navx/raw_accel/x topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawAccelY | ( | ) |
Publishes the raw acceleration rate (G) in the Y-axis to the navx/raw_accel/y topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawAccelZ | ( | ) |
Publishes the raw acceleration rate (G) in the Z-axis to the navx/raw_accel/z topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawGyro | ( | ) |
Provides a grouped publisher for the gyro rotation rate (in degrees/sec) in the X, Y, and Z axes to the navx/raw_gyro topic.
NOTE: This value is unprocessed, and should only be accessed by advanced users.
| void navXROSWrapper::PubRawGyroX | ( | ) |
Publishes the raw gyro rotation rate (in degrees/sec) in the X-axis to the navx/raw_gyro/x topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawGyroY | ( | ) |
Publishes the raw gyro rotation rate (in degrees/sec) in the Y-axis to the navx/raw_gyro/y topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawGyroZ | ( | ) |
Publishes the raw gyro rotation rate (in degrees/sec) in the X-axis to the navx/raw_gyro/z topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawMag | ( | ) |
Provides a grouped publishers to for the raw magnetometer readings (in µTesla) in the X, Y, and Z axes to the navx/raw_mag topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawMagX | ( | ) |
Publishes the raw magnetometer readings (in µTesla) in the X-axis to the navx/raw_mag/x topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawMagY | ( | ) |
Publishes the raw magnetometer readings (in µTesla) in the Y-axis to the navx/raw_mag/y topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRawMagZ | ( | ) |
Publishes the raw magnetometer readings (in µTesla) in the Z-axis to the navx/raw_mag/z topic.
NOTE: This value is unprocessed sand should only be used by advanced users.
| void navXROSWrapper::PubRoll | ( | ) |
Publishes the roll readings from the NavX sensor to the navx/roll topic.
| void navXROSWrapper::PubRollPitchYaw | ( | ) |
Provides a grouped publisher for roll, pitch, and yaw (-180 to 180 deg) to the navx/roll_pitch_yaw topic.
| void navXROSWrapper::PubTimestamp | ( | ) |
Publishes the timestamp of the last sensor message reported from the NavX to the navx/last_sensor_timestamp.
| void navXROSWrapper::PubVelocity | ( | ) |
Provides a grouped publisher for velocity (in meters/sec) in the X, Y, and Z axes to the navx/velocity topic.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as velocity measurements depend on the integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting velocities are not known to be accurate.
| void navXROSWrapper::PubVelX | ( | ) |
Publishes the velocity (in meters/sec) in the X-axis to the navx/velocity/x.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as velocity measurements depend on the integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting velocities are not known to be accurate.
| void navXROSWrapper::PubVelY | ( | ) |
Publishes the velocity (in meters/sec) in the Y-axis to the navx/velocity/y.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as velocity measurements depend on the integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting velocities are not known to be accurate.
| void navXROSWrapper::PubVelZ | ( | ) |
Publishes the velocity (in meters/sec) in the Z-axis to the navx/velocity/z.
NOTE: The method in the VMX-pi HAL where this accessor is implemented is experimental as velocity measurements depend on the integration of linear acceleration reported by MEMS accelerometers. Unfortunately, acceleration values from the MEMS sensor yield "noisy" values, therefore the resulting velocities are not known to be accurate.
| void navXROSWrapper::PubYaw | ( | ) |
Publishes the yaw readings (in degrees, from -180 to 180) from the NavX sensor to the navx/yaw topic.
| bool navXROSWrapper::Reset | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) |
Provides the ROS service to zero the yaw angle.
| req | Empty request service type defined in the ROS srv files. |
| res | Empty request service type defined in the ROS srv files. |
| bool navXROSWrapper::ResetDisplacement | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) |
Provides the ROS service to reset the displacement, meaning a new origin is set where this is invoked.
| req | Empty request service type defined in the ROS srv files. |
| res | Empty response service type defined in the ROS srv files. |
| void navXROSWrapper::Run_t | ( | ) |
Provides a method to call a thread of various Publishers of the NaxXROS library advertising sensor data to the ROS Master node.