15 #include <std_msgs/UInt32.h> 16 #include <std_msgs/Float64.h> 17 #include <std_msgs/Int8.h> 18 #include <std_msgs/Bool.h> 19 #include <nav_msgs/Odometry.h> 20 #include <sensor_msgs/BatteryState.h> 22 #include "std_msgs/String.h" 23 #include "boost/date_time/posix_time/posix_time.hpp" 25 #include "vda5050_msgs/State.h" 26 #include "vda5050_msgs/NodeStates.h" 27 #include "vda5050_msgs/NodeState.h" 28 #include "vda5050_msgs/EdgeStates.h" 29 #include "vda5050_msgs/EdgeState.h" 30 #include "vda5050_msgs/AGVPosition.h" 31 #include "vda5050_msgs/Loads.h" 32 #include "vda5050_msgs/ActionStates.h" 33 #include "vda5050_msgs/Errors.h" 34 #include "vda5050_msgs/Information.h" 35 #include "vda5050_msgs/SafetyState.h" 36 #include "vda5050_msgs/Visualization.h"
void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr &msg)
void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr &msg)
void LinkPublishTopics(ros::NodeHandle *nh)
vda5050_msgs::Visualization visMessage
void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr &msg)
void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr &msg)
void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr &msg)
void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr &msg)
void UpdateVisualization()
void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Time lastUpdateTimestamp
void LinkSubscriptionTopics(ros::NodeHandle *nh)
ros::Duration updateInterval
void PublishVisualization()
double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr &msg)
void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr &msg)