Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
velocity_controller::ControllerNode Class Reference

#include <controller_node.h>

Inheritance diagram for velocity_controller::ControllerNode:
Inheritance graph
[legend]

Public Member Functions

 ControllerNode (ros::NodeHandle &n)
 Construct a new Controller Node object. More...
 
- Public Member Functions inherited from velocity_controller::Controller
 Controller ()
 Construct a new Controller object. More...
 
void getSpeed (float *_v, float *_w)
 Returns the current speed values. More...
 
void setGoalRadius (float _r)
 Set the Goal Radius. More...
 
void setPath (std::shared_ptr< std::vector< PathPoint >> _path)
 Set the path the contorler has to follow. More...
 
void setPID (float _Kp, float _Ki, float _Kd)
 sets the control parameters More...
 
void setSpeedParams (float _max_v, float _max_w)
 Set the Speed Params of the controller. More...
 
void setState (state s)
 Set the State (run stop step wait_step) More...
 
void update (PathPoint _odom, float _delta_t)
 updates the controller with the current robot position More...
 

Public Attributes

ros::NodeHandle n_
 Node handler to the root node. More...
 
ros::NodeHandle n_param_
 Node handler to the current node. More...
 
std::unique_ptr< ros::Raterate_
 

Private Member Functions

void subCtrlCb (const std_msgs::String _cmd)
 
void subPathCb (const nav_msgs::Path::ConstPtr &_path)
 
void subPoseCb (const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
 

Private Attributes

float goal_r_
 
float Kd_val_
 
float Ki_val_
 
float Kp_val_
 
ros::Time last_update_
 
float max_vel_v_
 
float max_vel_w_
 
ros::Publisher pubCmdVel_
 
ros::Subscriber subCtrl_
 
ros::Subscriber subPath_
 
ros::Subscriber subPose_
 
std::string topic_cmdVel_
 
std::string topic_ctrl_
 
std::string topic_path_
 
std::string topic_pose_
 

Additional Inherited Members

- Protected Attributes inherited from velocity_controller::Controller
PathPoint current_pose_
 

Detailed Description

Definition at line 15 of file controller_node.h.

Constructor & Destructor Documentation

velocity_controller::ControllerNode::ControllerNode ( ros::NodeHandle n)

Construct a new Controller Node object.

Parameters
nthe node handle to subscribe topics

Definition at line 33 of file controller_node.cpp.

Member Function Documentation

void velocity_controller::ControllerNode::subCtrlCb ( const std_msgs::String  _cmd)
private

Definition at line 157 of file controller_node.cpp.

void velocity_controller::ControllerNode::subPathCb ( const nav_msgs::Path::ConstPtr &  _path)
private

Definition at line 106 of file controller_node.cpp.

void velocity_controller::ControllerNode::subPoseCb ( const geometry_msgs::PoseWithCovarianceStampedConstPtr &  _pose)
private

Definition at line 76 of file controller_node.cpp.

Member Data Documentation

float velocity_controller::ControllerNode::goal_r_
private

Definition at line 41 of file controller_node.h.

float velocity_controller::ControllerNode::Kd_val_
private

Definition at line 44 of file controller_node.h.

float velocity_controller::ControllerNode::Ki_val_
private

Definition at line 43 of file controller_node.h.

float velocity_controller::ControllerNode::Kp_val_
private

Definition at line 42 of file controller_node.h.

ros::Time velocity_controller::ControllerNode::last_update_
private

Definition at line 45 of file controller_node.h.

float velocity_controller::ControllerNode::max_vel_v_
private

Definition at line 39 of file controller_node.h.

float velocity_controller::ControllerNode::max_vel_w_
private

Definition at line 40 of file controller_node.h.

ros::NodeHandle velocity_controller::ControllerNode::n_

Node handler to the root node.

Definition at line 26 of file controller_node.h.

ros::NodeHandle velocity_controller::ControllerNode::n_param_

Node handler to the current node.

Definition at line 27 of file controller_node.h.

ros::Publisher velocity_controller::ControllerNode::pubCmdVel_
private

Definition at line 31 of file controller_node.h.

std::unique_ptr<ros::Rate> velocity_controller::ControllerNode::rate_

Definition at line 28 of file controller_node.h.

ros::Subscriber velocity_controller::ControllerNode::subCtrl_
private

Definition at line 34 of file controller_node.h.

ros::Subscriber velocity_controller::ControllerNode::subPath_
private

Definition at line 33 of file controller_node.h.

ros::Subscriber velocity_controller::ControllerNode::subPose_
private

Definition at line 32 of file controller_node.h.

std::string velocity_controller::ControllerNode::topic_cmdVel_
private

Definition at line 35 of file controller_node.h.

std::string velocity_controller::ControllerNode::topic_ctrl_
private

Definition at line 38 of file controller_node.h.

std::string velocity_controller::ControllerNode::topic_path_
private

Definition at line 37 of file controller_node.h.

std::string velocity_controller::ControllerNode::topic_pose_
private

Definition at line 36 of file controller_node.h.


The documentation for this class was generated from the following files:


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:29