Go to the documentation of this file.
9 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DSystemState.h>
10 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DSatellites.h>
11 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DDetailSatellites.h>
12 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DLocalMagneticField.h>
13 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DUTMPosition.h>
14 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DECEFPos.h>
15 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DNorthSeekingInitStatus.h>
16 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DOdometerState.h>
17 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DRawGNSS.h>
18 #include <kvh_geo_fog_3d_msgs/KvhGeoFog3DRawSensors.h>
24 #include <geometry_msgs/TransformStamped.h>
27 #include "sensor_msgs/Imu.h"
28 #include "sensor_msgs/NavSatFix.h"
29 #include "sensor_msgs/NavSatStatus.h"
30 #include "sensor_msgs/MagneticField.h"
31 #include "nav_msgs/Odometry.h"
32 #include "geometry_msgs/Quaternion.h"
33 #include "geometry_msgs/Vector3.h"
34 #include "geometry_msgs/Vector3Stamped.h"
35 #include "geometry_msgs/TwistWithCovarianceStamped.h"
void PublishUtmPosition(ros::Publisher &, utm_position_packet_t)
void PublishRawSensors(ros::Publisher &, raw_sensors_packet_t)
void PublishIMUSensorRawFLU(ros::Publisher &, raw_sensors_packet_t)
void PublishOdomSpeed(ros::Publisher &, system_state_packet_t, odometer_state_packet_t, double, double, bool)
void PublishNavSatFix(ros::Publisher &, system_state_packet_t)
void PublishIMU_RPY_ENU(ros::Publisher &, system_state_packet_t)
void PublishVelENUTwist(ros::Publisher &, system_state_packet_t, velocity_standard_deviation_packet_t)
void PublishMagField(ros::Publisher &, raw_sensors_packet_t)
void PublishEcefPosition(ros::Publisher &, ecef_position_packet_t)
tf2::Quaternion quatFromRPY(double roll, double pitch, double yaw)
void PublishSatellites(ros::Publisher &, satellites_packet_t)
void PublishRawGnss(ros::Publisher &, raw_gnss_packet_t)
double BoundFromZeroTo2Pi(const double)
void PublishSystemState(ros::Publisher &, system_state_packet_t)
void PublishRawNavSatFix(ros::Publisher &, system_state_packet_t, raw_gnss_packet_t)
global variables used to store packet information.
void PublishOdomNED(ros::Publisher &, system_state_packet_t, utm_position_packet_t, euler_orientation_standard_deviation_packet_t, body_velocity_packet_t)
void PublishIMU_RPY_NED_DEG(ros::Publisher &, system_state_packet_t)
void PublishIMURawFLU(ros::Publisher &, system_state_packet_t)
void PublishIMU_ENU(ros::Publisher &, system_state_packet_t, euler_orientation_standard_deviation_packet_t)
void PublishIMU_NED(ros::Publisher &, system_state_packet_t, euler_orientation_standard_deviation_packet_t)
void PublishIMU_RPY_NED(ros::Publisher &, system_state_packet_t)
void PublishKvhOdometerState(ros::Publisher &, odometer_state_packet_t)
void PublishSatellitesDetailed(ros::Publisher &, detailed_satellites_packet_t)
void PublishVelBodyTwistFLU(ros::Publisher &, system_state_packet_t, body_velocity_packet_t, velocity_standard_deviation_packet_t)
void PublishIMU_RPY_ENU_DEG(ros::Publisher &, system_state_packet_t)
void PublishNorthSeekingStatus(ros::Publisher &, north_seeking_status_packet_t)
void PublishLocalMagnetics(ros::Publisher &, local_magnetics_packet_t)
void PublishOdomENU(ros::Publisher &, system_state_packet_t, utm_position_packet_t, euler_orientation_standard_deviation_packet_t, body_velocity_packet_t)
void PublishVelNEDTwist(ros::Publisher &, system_state_packet_t, velocity_standard_deviation_packet_t)
void PublishVelBodyTwistFRD(ros::Publisher &, system_state_packet_t, body_velocity_packet_t, velocity_standard_deviation_packet_t)
double BoundFromNegPiToPi(const double)
void PublishOdomState(ros::Publisher &, odometer_state_packet_t, double)
void PublishIMURaw(ros::Publisher &, system_state_packet_t)
void PublishIMUSensorRaw(ros::Publisher &, raw_sensors_packet_t)