#include <map>#include <vector>#include <numeric>#include <ros/ros.h>#include <tf2/utils.h>#include <geometry_msgs/Pose.h>#include <geometry_msgs/PoseStamped.h>#include <geometry_msgs/Twist.h>#include <geometry_msgs/TwistStamped.h>#include <cpswarm_msgs/ArrayOfPositions.h>#include <cpswarm_msgs/Position.h>#include <cpswarm_msgs/Velocity.h>#include <cpswarm_msgs/ArrayOfVectors.h>#include <cpswarm_msgs/VectorStamped.h>

Go to the source code of this file.
Classes | |
| struct | cartesian_vector_t |
| A vector type in Cartesian format containing UUID of the corresponding CPS together with last updated time stamp. More... | |
| struct | polar_vector_t |
| A vector type in polar format containing UUID of the corresponding CPS together with last updated time stamp. More... | |
Typedefs | |
| typedef struct cartesian_vector_t | cartesian_vector_t |
| A vector type in Cartesian format containing UUID of the corresponding CPS together with last updated time stamp. More... | |
| typedef struct polar_vector_t | polar_vector_t |
| A vector type in polar format containing UUID of the corresponding CPS together with last updated time stamp. More... | |
Variables | |
| int | pos_init |
| The number of position messages to ignore during initialization. This is because the first messages are inaccurate. More... | |
| geometry_msgs::Pose | pose |
| Current position of the CPS. More... | |
| bool | pose_valid |
| Whether a valid position has been received. More... | |
| int | sample_size |
| The number of data samples to average over for reliable results. More... | |
| map< string, cartesian_vector_t > | swarm_positions |
| The absolute positions of all known swarm members. More... | |
| map< string, polar_vector_t > | swarm_positions_rel |
| The relative positions of all known swarm members. More... | |
| map< string, polar_vector_t > | swarm_velocities |
| The velocities of all known swarm members. More... | |
| int | vel_init |
| The number of velocity messages to ignore during initialization. This is because the first messages are inaccurate. More... | |
| bool | vel_valid |
| Whether a valid velocity has been received. More... | |
| geometry_msgs::Twist | velo |
| Current velocity of the CPS. More... | |
| typedef struct cartesian_vector_t cartesian_vector_t |
A vector type in Cartesian format containing UUID of the corresponding CPS together with last updated time stamp.
| typedef struct polar_vector_t polar_vector_t |
A vector type in polar format containing UUID of the corresponding CPS together with last updated time stamp.
| int pos_init |
The number of position messages to ignore during initialization. This is because the first messages are inaccurate.
Definition at line 85 of file swarm_kinematics_exchanger.h.
| geometry_msgs::Pose pose |
Current position of the CPS.
Definition at line 45 of file swarm_kinematics_exchanger.h.
| bool pose_valid |
Whether a valid position has been received.
Definition at line 50 of file swarm_kinematics_exchanger.h.
| int sample_size |
The number of data samples to average over for reliable results.
Definition at line 80 of file swarm_kinematics_exchanger.h.
| map<string, cartesian_vector_t> swarm_positions |
The absolute positions of all known swarm members.
Definition at line 65 of file swarm_kinematics_exchanger.h.
| map<string, polar_vector_t> swarm_positions_rel |
The relative positions of all known swarm members.
Definition at line 70 of file swarm_kinematics_exchanger.h.
| map<string, polar_vector_t> swarm_velocities |
The velocities of all known swarm members.
Definition at line 75 of file swarm_kinematics_exchanger.h.
| int vel_init |
The number of velocity messages to ignore during initialization. This is because the first messages are inaccurate.
Definition at line 90 of file swarm_kinematics_exchanger.h.
| bool vel_valid |
Whether a valid velocity has been received.
Definition at line 60 of file swarm_kinematics_exchanger.h.
| geometry_msgs::Twist velo |
Current velocity of the CPS.
Definition at line 55 of file swarm_kinematics_exchanger.h.