56 for(
const auto& elem : topicList)
58 ss<<
"/" << elem.second;
62 nh->
advertise<vda5050_msgs::Visualization>(ss.str(),1000);
70 for(
const auto& elem : topicList)
74 else if (
CheckTopic(elem.first,
"positionInitialized"))
76 else if (
CheckTopic(elem.first,
"localizationScore"))
78 else if (
CheckTopic(elem.first,
"deviationRange"))
84 else if (
CheckTopic(elem.first,
"mapDescription"))
94 msg->pose.pose.orientation.x,
95 msg->pose.pose.orientation.y,
96 msg->pose.pose.orientation.z,
97 msg->pose.pose.orientation.w);
99 double roll, pitch, yaw;
100 m.getRPY(roll,pitch,yaw);
113 visMessage.agvPosition.x=msg->pose.pose.position.x;
114 visMessage.agvPosition.y=msg->pose.pose.position.y;
125 visMessage.velocity.vx=msg->twist.twist.linear.x;
126 visMessage.velocity.vy=msg->twist.twist.linear.y;
129 visMessage.velocity.omega=msg->twist.twist.angular.z;
135 visMessage.agvPosition.positionInitialized=msg->positionInitialized;
136 visMessage.agvPosition.localizationScore=msg->localizationScore;
137 visMessage.agvPosition.deviationRange=msg->deviationRange;
142 visMessage.agvPosition.mapDescription=msg->mapDescription;
146 visMessage.agvPosition.positionInitialized=msg->data;
150 if (
CheckRange(0.0,1.0,msg->data,
"AGV Position Localization Score"))
152 visMessage.agvPosition.localizationScore=msg->data;
157 visMessage.agvPosition.deviationRange=msg->data;
165 visMessage.agvPosition.mapDescription=msg->data;
168 int main(
int argc,
char **argv)
170 ros::init(argc, argv,
"visualization_deamon");