packet_publisher.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // KVH
4 #include "an_packet_protocol.h"
5 #include "spatial_packets.h"
7 
8 // CUSTOM ROS MESSAGES
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>
19 
20 // ROS
21 #include <ros/ros.h>
24 #include <geometry_msgs/TransformStamped.h>
25 
26 // Standard ROS msgs
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"
36 
37 
38 // Bound rotations
39 double BoundFromNegPiToPi(const double);
40 double BoundFromNegPiToPi(const float);
41 double BoundFromZeroTo2Pi(const double);
42 double BoundFromZeroTo2Pi(const float);
43 
44 // RPY to quaternion conversion
45 tf2::Quaternion quatFromRPY(double roll, double pitch, double yaw);
46 
47 // Custom ROS Message
58 
59 // Standard ROS Messages
83 
PublishUtmPosition
void PublishUtmPosition(ros::Publisher &, utm_position_packet_t)
Definition: packet_publisher.cpp:144
PublishRawSensors
void PublishRawSensors(ros::Publisher &, raw_sensors_packet_t)
Definition: packet_publisher.cpp:201
velocity_standard_deviation_packet_t
Definition: spatial_packets.h:377
ros::Publisher
PublishIMUSensorRawFLU
void PublishIMUSensorRawFLU(ros::Publisher &, raw_sensors_packet_t)
Definition: packet_publisher.cpp:756
satellites_packet_t
Definition: spatial_packets.h:428
north_seeking_status_packet_t
Definition: spatial_packets.h:744
PublishOdomSpeed
void PublishOdomSpeed(ros::Publisher &, system_state_packet_t, odometer_state_packet_t, double, double, bool)
Definition: packet_publisher.cpp:702
PublishNavSatFix
void PublishNavSatFix(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:483
ros.h
PublishIMU_RPY_ENU
void PublishIMU_RPY_ENU(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:442
detailed_satellites_packet_t
Definition: spatial_packets.h:476
PublishVelENUTwist
void PublishVelENUTwist(ros::Publisher &, system_state_packet_t, velocity_standard_deviation_packet_t)
Definition: packet_publisher.cpp:791
PublishMagField
void PublishMagField(ros::Publisher &, raw_sensors_packet_t)
Definition: packet_publisher.cpp:562
PublishEcefPosition
void PublishEcefPosition(ros::Publisher &, ecef_position_packet_t)
Definition: packet_publisher.cpp:156
quatFromRPY
tf2::Quaternion quatFromRPY(double roll, double pitch, double yaw)
Definition: packet_publisher.cpp:38
PublishSatellites
void PublishSatellites(ros::Publisher &, satellites_packet_t)
Definition: packet_publisher.cpp:88
raw_gnss_packet_t
Definition: spatial_packets.h:402
an_packet_protocol.h
PublishRawGnss
void PublishRawGnss(ros::Publisher &, raw_gnss_packet_t)
Definition: packet_publisher.cpp:226
transform_broadcaster.h
BoundFromZeroTo2Pi
double BoundFromZeroTo2Pi(const double)
Definition: packet_publisher.cpp:28
PublishSystemState
void PublishSystemState(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:48
PublishRawNavSatFix
void PublishRawNavSatFix(ros::Publisher &, system_state_packet_t, raw_gnss_packet_t)
Definition: packet_publisher.cpp:522
kvh_geo_fog_3d_global_vars.hpp
global variables used to store packet information.
odometer_state_packet_t
Definition: spatial_packets.h:586
PublishOdomNED
void PublishOdomNED(ros::Publisher &, system_state_packet_t, utm_position_packet_t, euler_orientation_standard_deviation_packet_t, body_velocity_packet_t)
Definition: packet_publisher.cpp:575
body_velocity_packet_t
Definition: spatial_packets.h:502
euler_orientation_standard_deviation_packet_t
Definition: spatial_packets.h:382
utm_position_packet_t
Definition: spatial_packets.h:491
Quaternion.h
PublishIMU_RPY_NED_DEG
void PublishIMU_RPY_NED_DEG(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:424
ecef_position_packet_t
Definition: spatial_packets.h:486
PublishIMURawFLU
void PublishIMURawFLU(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:292
local_magnetics_packet_t
Definition: spatial_packets.h:581
PublishIMU_ENU
void PublishIMU_ENU(ros::Publisher &, system_state_packet_t, euler_orientation_standard_deviation_packet_t)
Definition: packet_publisher.cpp:366
PublishIMU_NED
void PublishIMU_NED(ros::Publisher &, system_state_packet_t, euler_orientation_standard_deviation_packet_t)
Definition: packet_publisher.cpp:324
PublishIMU_RPY_NED
void PublishIMU_RPY_NED(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:407
PublishKvhOdometerState
void PublishKvhOdometerState(ros::Publisher &, odometer_state_packet_t)
Definition: packet_publisher.cpp:188
PublishSatellitesDetailed
void PublishSatellitesDetailed(ros::Publisher &, detailed_satellites_packet_t)
Definition: packet_publisher.cpp:102
PublishVelBodyTwistFLU
void PublishVelBodyTwistFLU(ros::Publisher &, system_state_packet_t, body_velocity_packet_t, velocity_standard_deviation_packet_t)
Definition: packet_publisher.cpp:807
tf2::Quaternion
PublishIMU_RPY_ENU_DEG
void PublishIMU_RPY_ENU_DEG(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:462
PublishNorthSeekingStatus
void PublishNorthSeekingStatus(ros::Publisher &, north_seeking_status_packet_t)
Definition: packet_publisher.cpp:167
PublishLocalMagnetics
void PublishLocalMagnetics(ros::Publisher &, local_magnetics_packet_t)
Definition: packet_publisher.cpp:133
PublishOdomENU
void PublishOdomENU(ros::Publisher &, system_state_packet_t, utm_position_packet_t, euler_orientation_standard_deviation_packet_t, body_velocity_packet_t)
Definition: packet_publisher.cpp:623
PublishVelNEDTwist
void PublishVelNEDTwist(ros::Publisher &, system_state_packet_t, velocity_standard_deviation_packet_t)
Definition: packet_publisher.cpp:775
PublishVelBodyTwistFRD
void PublishVelBodyTwistFRD(ros::Publisher &, system_state_packet_t, body_velocity_packet_t, velocity_standard_deviation_packet_t)
Definition: packet_publisher.cpp:827
BoundFromNegPiToPi
double BoundFromNegPiToPi(const double)
Definition: packet_publisher.cpp:8
PublishOdomState
void PublishOdomState(ros::Publisher &, odometer_state_packet_t, double)
Definition: packet_publisher.cpp:679
system_state_packet_t
Definition: spatial_packets.h:246
PublishIMURaw
void PublishIMURaw(ros::Publisher &, system_state_packet_t)
Definition: packet_publisher.cpp:262
spatial_packets.h
raw_sensors_packet_t
Definition: spatial_packets.h:392
PublishIMUSensorRaw
void PublishIMUSensorRaw(ros::Publisher &, raw_sensors_packet_t)
Definition: packet_publisher.cpp:734


kvh_geo_fog_3d_driver
Author(s): Trevor Bostic , Zach LaCelle
autogenerated on Wed Mar 2 2022 00:28:57