#include "an_packet_protocol.h"#include "spatial_packets.h"#include "kvh_geo_fog_3d_global_vars.hpp"#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DSystemState.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DSatellites.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DDetailSatellites.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DLocalMagneticField.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DUTMPosition.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DECEFPos.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DNorthSeekingInitStatus.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DOdometerState.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DRawGNSS.h>#include <kvh_geo_fog_3d_msgs/KvhGeoFog3DRawSensors.h>#include <ros/ros.h>#include "tf2/LinearMath/Quaternion.h"#include <tf2_ros/transform_broadcaster.h>#include <geometry_msgs/TransformStamped.h>#include "sensor_msgs/Imu.h"#include "sensor_msgs/NavSatFix.h"#include "sensor_msgs/NavSatStatus.h"#include "sensor_msgs/MagneticField.h"#include "nav_msgs/Odometry.h"#include "geometry_msgs/Quaternion.h"#include "geometry_msgs/Vector3.h"#include "geometry_msgs/Vector3Stamped.h"#include "geometry_msgs/TwistWithCovarianceStamped.h"

Go to the source code of this file.
| double BoundFromNegPiToPi | ( | const double | ) | 
Definition at line 8 of file packet_publisher.cpp.
| double BoundFromNegPiToPi | ( | const float | ) | 
Definition at line 18 of file packet_publisher.cpp.
| double BoundFromZeroTo2Pi | ( | const double | ) | 
Definition at line 28 of file packet_publisher.cpp.
| double BoundFromZeroTo2Pi | ( | const float | ) | 
Definition at line 33 of file packet_publisher.cpp.
| void PublishEcefPosition | ( | ros::Publisher & | , | 
| ecef_position_packet_t | |||
| ) | 
Definition at line 156 of file packet_publisher.cpp.
| void PublishIMU_ENU | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| euler_orientation_standard_deviation_packet_t | |||
| ) | 
Definition at line 366 of file packet_publisher.cpp.
| void PublishIMU_NED | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| euler_orientation_standard_deviation_packet_t | |||
| ) | 
Definition at line 324 of file packet_publisher.cpp.
| void PublishIMU_RPY_ENU | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 442 of file packet_publisher.cpp.
| void PublishIMU_RPY_ENU_DEG | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 462 of file packet_publisher.cpp.
| void PublishIMU_RPY_NED | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 407 of file packet_publisher.cpp.
| void PublishIMU_RPY_NED_DEG | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 424 of file packet_publisher.cpp.
| void PublishIMURaw | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 262 of file packet_publisher.cpp.
| void PublishIMURawFLU | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 292 of file packet_publisher.cpp.
| void PublishIMUSensorRaw | ( | ros::Publisher & | , | 
| raw_sensors_packet_t | |||
| ) | 
Definition at line 734 of file packet_publisher.cpp.
| void PublishIMUSensorRawFLU | ( | ros::Publisher & | , | 
| raw_sensors_packet_t | |||
| ) | 
Definition at line 756 of file packet_publisher.cpp.
| void PublishKvhOdometerState | ( | ros::Publisher & | , | 
| odometer_state_packet_t | |||
| ) | 
Definition at line 188 of file packet_publisher.cpp.
| void PublishLocalMagnetics | ( | ros::Publisher & | , | 
| local_magnetics_packet_t | |||
| ) | 
Definition at line 133 of file packet_publisher.cpp.
| void PublishMagField | ( | ros::Publisher & | , | 
| raw_sensors_packet_t | |||
| ) | 
Definition at line 562 of file packet_publisher.cpp.
| void PublishNavSatFix | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 483 of file packet_publisher.cpp.
| void PublishNorthSeekingStatus | ( | ros::Publisher & | , | 
| north_seeking_status_packet_t | |||
| ) | 
Definition at line 167 of file packet_publisher.cpp.
| void PublishOdomENU | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| utm_position_packet_t | , | ||
| euler_orientation_standard_deviation_packet_t | , | ||
| body_velocity_packet_t | |||
| ) | 
Definition at line 623 of file packet_publisher.cpp.
| void PublishOdomNED | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| utm_position_packet_t | , | ||
| euler_orientation_standard_deviation_packet_t | , | ||
| body_velocity_packet_t | |||
| ) | 
Definition at line 575 of file packet_publisher.cpp.
| void PublishOdomSpeed | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| odometer_state_packet_t | , | ||
| double | , | ||
| double | , | ||
| bool | |||
| ) | 
Definition at line 702 of file packet_publisher.cpp.
| void PublishOdomState | ( | ros::Publisher & | , | 
| odometer_state_packet_t | , | ||
| double | |||
| ) | 
Definition at line 679 of file packet_publisher.cpp.
| void PublishRawGnss | ( | ros::Publisher & | , | 
| raw_gnss_packet_t | |||
| ) | 
Definition at line 226 of file packet_publisher.cpp.
| void PublishRawNavSatFix | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| raw_gnss_packet_t | |||
| ) | 
Definition at line 522 of file packet_publisher.cpp.
| void PublishRawSensors | ( | ros::Publisher & | , | 
| raw_sensors_packet_t | |||
| ) | 
Definition at line 201 of file packet_publisher.cpp.
| void PublishSatellites | ( | ros::Publisher & | , | 
| satellites_packet_t | |||
| ) | 
Definition at line 88 of file packet_publisher.cpp.
| void PublishSatellitesDetailed | ( | ros::Publisher & | , | 
| detailed_satellites_packet_t | |||
| ) | 
Definition at line 102 of file packet_publisher.cpp.
| void PublishSystemState | ( | ros::Publisher & | , | 
| system_state_packet_t | |||
| ) | 
Definition at line 48 of file packet_publisher.cpp.
| void PublishUtmPosition | ( | ros::Publisher & | , | 
| utm_position_packet_t | |||
| ) | 
Definition at line 144 of file packet_publisher.cpp.
| void PublishVelBodyTwistFLU | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| body_velocity_packet_t | , | ||
| velocity_standard_deviation_packet_t | |||
| ) | 
Definition at line 807 of file packet_publisher.cpp.
| void PublishVelBodyTwistFRD | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| body_velocity_packet_t | , | ||
| velocity_standard_deviation_packet_t | |||
| ) | 
Definition at line 827 of file packet_publisher.cpp.
| void PublishVelENUTwist | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| velocity_standard_deviation_packet_t | |||
| ) | 
Definition at line 791 of file packet_publisher.cpp.
| void PublishVelNEDTwist | ( | ros::Publisher & | , | 
| system_state_packet_t | , | ||
| velocity_standard_deviation_packet_t | |||
| ) | 
Definition at line 775 of file packet_publisher.cpp.
| tf2::Quaternion quatFromRPY | ( | double | roll, | 
| double | pitch, | ||
| double | yaw | ||
| ) | 
Definition at line 38 of file packet_publisher.cpp.