7     nh.
param(this_node::getName() + 
"/loop_rate", loop_rate, 5.0);
    10     nh.
param(this_node::getName() + 
"/queue_size", queue_size, 1);
    17     vel_pub = 
nh.
advertise<geometry_msgs::Twist>(
"vel_controller/target_velocity", queue_size, 
true);
    34     geometry_msgs::Pose goal_pose;
    35     goal_pose.position = goal;
    38     ROS_DEBUG(
"Goal bearing %.2f", goal_bear);
    41     if (
pos.
dist(goal_pose) < M_PI / 2.0)
    42         velocity *= sin(
pos.
dist(goal_pose));
    45     geometry_msgs::Vector3 vel;
    46     vel.x = velocity * -sin(goal_bear); 
    47     vel.y = velocity * cos(goal_bear);
    49     ROS_DEBUG(
"Velocity (%.2f,%.2f)", vel.x, vel.y);
    62     geometry_msgs::Twist target_velocity;
    74     double mag = hypot(dx, dy);
    75     double dir = atan2(dy, dx);
    78     cpswarm_msgs::Vector rel_vel;
    79     rel_vel.magnitude = mag;
    80     rel_vel.direction = dir;
    87     if (msg->header.stamp.isValid())
 double bearing(geometry_msgs::Pose p) const 
void move(geometry_msgs::Vector3 velocity)
Move the CPS with a given velocity. 
velocity(double altitude)
Constructor that initializes the private member variables. 
void publish(const boost::shared_ptr< M > &message) const 
#define ROS_DEBUG_THROTTLE(rate,...)
A class to provide velocity related functionalities. 
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. 
cpswarm_msgs::Vector rel_velocity(geometry_msgs::Vector3 v) const 
Compute the velocity difference of the CPS to a given velocity. 
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
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. 
geometry_msgs::Twist current_vel
Current velocity of the CPS. 
bool vel_valid
Whether a valid velocity has been received. 
~velocity()
Destructor that deletes the private member objects. 
Subscriber vel_sub
Subscriber for the velocity of the CPS. 
Rate * rate
The loop rate object for running the behavior control loops at a specific frequency. 
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 ...
NodeHandle nh
A node handle for the main ROS node. 
Publisher vel_pub
Publisher for sending the target velocity of the CPS to the velocity controller in the abstraction li...
void vel_callback(const geometry_msgs::TwistStamped::ConstPtr &msg)
Callback function for velocity updates. 
double dist(geometry_msgs::Pose p) const 
ROSCPP_DECL void spinOnce()