42 double dx = v.x -
velo.linear.x;
43 double dy = v.y -
velo.linear.y;
44 double mag = hypot(dx, dy);
45 double dir = atan2(dy, dx);
48 cpswarm_msgs::Vector rel_vel;
49 rel_vel.magnitude = mag;
50 rel_vel.direction = dir;
61 if (msg->header.stamp.isValid())
72 void vel_callback (
const geometry_msgs::TwistStamped::ConstPtr& msg)
75 if (msg->header.stamp.isValid())
93 string uuid = msg.swarmio.node;
138 string uuid = msg.swarmio.node;
148 cpswarm_msgs::Vector velocity =
rel_velocity(msg.velocity.linear);
166 int main (
int argc,
char **argv)
169 init(argc, argv,
"swarm_kinematics_exchanger");
174 nh.
param(this_node::getName() +
"/loop_rate", loop_rate, 1.5);
176 nh.
param(this_node::getName() +
"/queue_size", queue_size, 1);
178 nh.
param(this_node::getName() +
"/timeout", timeout, 20.0);
188 Publisher outgoing_position_publisher = nh.
advertise<cpswarm_msgs::Position>(
"position", queue_size);
189 Publisher outgoing_velocity_publisher = nh.
advertise<cpswarm_msgs::Velocity>(
"velocity", queue_size);
190 Publisher incoming_position_publisher = nh.
advertise<cpswarm_msgs::ArrayOfPositions>(
"swarm_position", queue_size);
191 Publisher incoming_rel_position_publisher = nh.
advertise<cpswarm_msgs::ArrayOfVectors>(
"swarm_position_rel", queue_size);
192 Publisher incoming_rel_velocity_publisher = nh.
advertise<cpswarm_msgs::ArrayOfVectors>(
"swarm_velocity_rel", queue_size);
195 Rate rate(loop_rate);
207 cpswarm_msgs::ArrayOfPositions swarm_position;
208 cpswarm_msgs::ArrayOfVectors swarm_position_rel;
209 cpswarm_msgs::ArrayOfVectors swarm_velocity_rel;
214 swarm_position.positions.clear();
215 swarm_position_rel.vectors.clear();
216 swarm_velocity_rel.vectors.clear();
221 if ((Time::now() - member->second.stamp) >
Duration(timeout)) {
229 cpswarm_msgs::Position position;
230 position.header.stamp = Time::now();
231 position.swarmio.node = member->first;
234 position.pose.position.x = accumulate(member->second.x.begin(), member->second.x.end(), 0.0) / member->second.x.size();
235 position.pose.position.y = accumulate(member->second.y.begin(), member->second.y.end(), 0.0) / member->second.y.size();
238 swarm_position.positions.push_back(position);
248 if ((Time::now() - member->second.stamp) >
Duration(timeout)) {
256 cpswarm_msgs::VectorStamped position;
257 position.header.stamp = Time::now();
258 position.swarmio.node = member->first;
261 position.vector.magnitude = accumulate(member->second.mag.begin(), member->second.mag.end(), 0.0) / member->second.mag.size();
264 float sines = accumulate(member->second.dir.begin(), member->second.dir.end(), 0.0,
acc_sin) / member->second.dir.size();
265 float cosines = accumulate(member->second.dir.begin(), member->second.dir.end(), 0.0,
acc_cos) / member->second.dir.size();
266 position.vector.direction = atan2(sines, cosines);
269 swarm_position_rel.vectors.push_back(position);
279 if ((Time::now() - member->second.stamp) >
Duration(timeout)) {
287 cpswarm_msgs::VectorStamped velocity;
288 velocity.header.stamp = Time::now();
289 velocity.swarmio.node = member->first;
292 velocity.vector.magnitude = accumulate(member->second.mag.begin(), member->second.mag.end(), 0.0) / member->second.mag.size();
295 float sines = accumulate(member->second.dir.begin(), member->second.dir.end(), 0.0,
acc_sin) / member->second.dir.size();
296 float cosines = accumulate(member->second.dir.begin(), member->second.dir.end(), 0.0,
acc_cos) / member->second.dir.size();
297 velocity.vector.direction = atan2(sines, cosines);
300 swarm_velocity_rel.vectors.push_back(velocity);
308 incoming_position_publisher.publish(swarm_position);
309 incoming_rel_position_publisher.publish(swarm_position_rel);
310 incoming_rel_velocity_publisher.publish(swarm_velocity_rel);
313 cpswarm_msgs::Position position;
314 position.header.stamp = Time::now();
315 position.swarmio.name =
"position";
316 position.pose =
pose;
317 outgoing_position_publisher.
publish(position);
318 cpswarm_msgs::Velocity velocity;
319 velocity.header.stamp = Time::now();
320 velocity.swarmio.name =
"velocity";
321 velocity.velocity =
velo;
322 outgoing_velocity_publisher.publish(velocity);
geometry_msgs::Twist velo
Current velocity of the CPS.
map< string, polar_vector_t > swarm_positions_rel
The relative positions of all known swarm members.
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void init(const M_string &remappings)
int vel_init
The number of velocity messages to ignore during initialization. This is because the first messages a...
#define ROS_DEBUG_ONCE(...)
map< string, polar_vector_t > swarm_velocities
The velocities of all known swarm members.
void swarm_position_callback(cpswarm_msgs::Position msg)
Callback function for position updates from other swarm members.
A vector type in polar format containing UUID of the corresponding CPS together with last updated tim...
void vel_callback(const geometry_msgs::TwistStamped::ConstPtr &msg)
Callback function for velocity updates.
geometry_msgs::Pose pose
Current position of the CPS.
int main(int argc, char **argv)
A ROS node that exchanges relative kinematics between CPSs in a swarm.
float acc_sin(float x, float y)
Accumulate sines.
void pose_callback(const geometry_msgs::PoseStamped::ConstPtr &msg)
Callback function for position updates.
int pos_init
The number of position messages to ignore during initialization. This is because the first messages a...
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void fromMsg(const A &, B &b)
bool pose_valid
Whether a valid position has been received.
map< string, cartesian_vector_t > swarm_positions
The absolute positions of all known swarm members.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int sample_size
The number of data samples to average over for reliable results.
double getYaw(const A &a)
float acc_cos(float x, float y)
Accumulate cosines.
bool vel_valid
Whether a valid velocity has been received.
void swarm_velocity_callback(cpswarm_msgs::Velocity msg)
Callback function for velocity updates from other swarm members.
A vector type in Cartesian format containing UUID of the corresponding CPS together with last updated...
ROSCPP_DECL void spinOnce()
cpswarm_msgs::Vector rel_velocity(geometry_msgs::Vector3 v)
Compute the velocity difference of the CPS to a given velocity.
double get_yaw()
Get the yaw orientation of the current pose.