velocity.cpp
Go to the documentation of this file.
1 #include "velocity.h"
2 
3 velocity::velocity (double altitude) : pos(altitude)
4 {
5  // read parameters
6  double loop_rate;
7  nh.param(this_node::getName() + "/loop_rate", loop_rate, 5.0);
8  rate = new Rate(loop_rate);
9  int queue_size;
10  nh.param(this_node::getName() + "/queue_size", queue_size, 1);
11 
12  // no velocity received yet
13  vel_valid = false;
14 
15  // init publishers and subscribers
16  vel_sub = nh.subscribe("vel_provider/velocity", queue_size, &velocity::vel_callback, this);
17  vel_pub = nh.advertise<geometry_msgs::Twist>("vel_controller/target_velocity", queue_size, true);
18 
19  // init velocity
20  while (ok() && vel_valid == false) {
21  rate->sleep();
22  spinOnce();
23  }
24 }
25 
27 {
28  delete rate;
29 }
30 
31 geometry_msgs::Vector3 velocity::compute_velocity (geometry_msgs::Point goal, double velocity)
32 {
33  // relative bearing of goal
34  geometry_msgs::Pose goal_pose;
35  goal_pose.position = goal;
36  double goal_bear = pos.bearing(goal_pose);
37 
38  ROS_DEBUG("Goal bearing %.2f", goal_bear);
39 
40  // limit velocity for small distances
41  if (pos.dist(goal_pose) < M_PI / 2.0)
42  velocity *= sin(pos.dist(goal_pose));
43 
44  // velocity components in goal direction
45  geometry_msgs::Vector3 vel;
46  vel.x = velocity * -sin(goal_bear); // bearing relative to cps heading
47  vel.y = velocity * cos(goal_bear);
48 
49  ROS_DEBUG("Velocity (%.2f,%.2f)", vel.x, vel.y);
50 
51  return vel;
52 }
53 
54 geometry_msgs::Vector3 velocity::get_velocity () const
55 {
56  return current_vel.linear;
57 }
58 
59 void velocity::move (geometry_msgs::Vector3 velocity)
60 {
61  // create target velocity message
62  geometry_msgs::Twist target_velocity;
63  target_velocity.linear = velocity;
64 
65  // send target velocity to cps controller
66  vel_pub.publish(target_velocity);
67 }
68 
69 cpswarm_msgs::Vector velocity::rel_velocity (geometry_msgs::Vector3 v) const
70 {
71  // compute relative velocity
72  double dx = v.x - current_vel.linear.x;
73  double dy = v.y - current_vel.linear.y;
74  double mag = hypot(dx, dy);
75  double dir = atan2(dy, dx);
76 
77  // return relative velocity
78  cpswarm_msgs::Vector rel_vel;
79  rel_vel.magnitude = mag;
80  rel_vel.direction = dir;
81  return rel_vel;
82 }
83 
84 void velocity::vel_callback (const geometry_msgs::TwistStamped::ConstPtr& msg)
85 {
86  // valid pose received
87  if (msg->header.stamp.isValid())
88  vel_valid = true;
89 
90  current_vel = msg->twist;
91 
92  ROS_DEBUG_THROTTLE(1, "Velocity [%.2f, %.2f]", current_vel.linear.x, current_vel.linear.y);
93 }
double bearing(geometry_msgs::Pose p) const
void move(geometry_msgs::Vector3 velocity)
Move the CPS with a given velocity.
Definition: velocity.cpp:59
velocity(double altitude)
Constructor that initializes the private member variables.
Definition: velocity.cpp:3
void publish(const boost::shared_ptr< M > &message) const
#define ROS_DEBUG_THROTTLE(rate,...)
A class to provide velocity related functionalities.
Definition: velocity.h:18
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
position pos
A helper object for position related tasks.
Definition: velocity.h:89
cpswarm_msgs::Vector rel_velocity(geometry_msgs::Vector3 v) const
Compute the velocity difference of the CPS to a given velocity.
Definition: velocity.cpp:69
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::Vector3 get_velocity() const
Get the current velocity of the CPS.
Definition: velocity.cpp:54
bool sleep()
geometry_msgs::Twist current_vel
Current velocity of the CPS.
Definition: velocity.h:94
bool vel_valid
Whether a valid velocity has been received.
Definition: velocity.h:99
~velocity()
Destructor that deletes the private member objects.
Definition: velocity.cpp:26
Subscriber vel_sub
Subscriber for the velocity of the CPS.
Definition: velocity.h:74
Rate * rate
The loop rate object for running the behavior control loops at a specific frequency.
Definition: velocity.h:84
geometry_msgs::Vector3 compute_velocity(geometry_msgs::Point goal, double velocity)
Compute the velocity vector required to reach a goal point from the current position while traveling ...
Definition: velocity.cpp:31
NodeHandle nh
A node handle for the main ROS node.
Definition: velocity.h:69
Publisher vel_pub
Publisher for sending the target velocity of the CPS to the velocity controller in the abstraction li...
Definition: velocity.h:79
void vel_callback(const geometry_msgs::TwistStamped::ConstPtr &msg)
Callback function for velocity updates.
Definition: velocity.cpp:84
double dist(geometry_msgs::Pose p) const
ROSCPP_DECL void spinOnce()
#define ROS_DEBUG(...)


swarm_behaviors_velocity
Author(s):
autogenerated on Sat Feb 6 2021 03:11:35