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...
 
 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...
 
int getGoodId ()
 
int getOrderId ()
 
int getOrderStatus ()
 
size_t getProgress ()
 return progress, More...
 
void getSpeed (float *_v, float *_w)
 Returns the current speed values. More...
 
int getStatus ()
 
bool isActive ()
 return progress, passed waypoints on the given path More...
 
void setGoalRadius (float _r)
 Set the Goal Radius. More...
 
void setGoodId (int)
 
void setOrderId (int)
 
void setOrderStatus (int)
 
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 onCommandReceived (const std_msgs::String command)
 
void onGoalReceived (const tuw_local_controller_msgs::ExecutePathGoalConstPtr &goal)
 
void onPoseReceived (const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
 
void publishControllerState (const nav_msgs::Path &path)
 
void publishState ()
 
void setupController (const nav_msgs::Path &path, const ControllerConfig &config)
 
void subCtrlCb (const std_msgs::String _cmd)
 
void subPathCb (const nav_msgs::Path::ConstPtr &_path)
 
void subPoseCb (const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
 

Private Attributes

actionlib::SimpleActionServer< tuw_local_controller_msgs::ExecutePathAction > action_server
 
geometry_msgs::Twist cmd_
 
ros::Subscriber command_subscriber
 
tuw_nav_msgs::ControllerState ctrl_state_
 
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::Subscriber pose_subscriber
 
ros::Publisher pubCmdVel_
 
ros::Publisher pubState_
 
ros::Publisher state_publisher
 
ros::Subscriber subCtrl_
 
ros::Subscriber subPath_
 
ros::Subscriber subPose_
 
ros::Publisher twist_publisher
 

Additional Inherited Members

- Protected Attributes inherited from velocity_controller::Controller
PathPoint current_pose_
 

Detailed Description

Definition at line 16 of file controller_node.h.

Constructor & Destructor Documentation

◆ ControllerNode() [1/2]

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

Construct a new Controller Node object.

Parameters
nthe node handle to subscribe topics

Definition at line 26 of file controller_node.cpp.

◆ ControllerNode() [2/2]

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

Construct a new Controller Node object.

Parameters
nthe node handle to subscribe topics

Member Function Documentation

◆ onCommandReceived()

void velocity_controller::ControllerNode::onCommandReceived ( const std_msgs::String  command)
private

Definition at line 77 of file local_controller_node.cpp.

◆ onGoalReceived()

void velocity_controller::ControllerNode::onGoalReceived ( const tuw_local_controller_msgs::ExecutePathGoalConstPtr &  goal)
private

Definition at line 92 of file local_controller_node.cpp.

◆ onPoseReceived()

void velocity_controller::ControllerNode::onPoseReceived ( const geometry_msgs::PoseWithCovarianceStampedConstPtr &  pose)
private

Definition at line 36 of file local_controller_node.cpp.

◆ publishControllerState()

void velocity_controller::ControllerNode::publishControllerState ( const nav_msgs::Path &  path)
private

Definition at line 63 of file local_controller_node.cpp.

◆ publishState()

void velocity_controller::ControllerNode::publishState ( )
private

Definition at line 98 of file controller_node.cpp.

◆ setupController()

void velocity_controller::ControllerNode::setupController ( const nav_msgs::Path &  path,
const ControllerConfig config 
)
private

Definition at line 141 of file local_controller_node.cpp.

◆ subCtrlCb()

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

Definition at line 163 of file controller_node.cpp.

◆ subPathCb()

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

Definition at line 109 of file controller_node.cpp.

◆ subPoseCb()

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

Definition at line 68 of file controller_node.cpp.

Member Data Documentation

◆ action_server

actionlib::SimpleActionServer<tuw_local_controller_msgs::ExecutePathAction> velocity_controller::ControllerNode::action_server
private

Definition at line 50 of file local_controller_node.h.

◆ cmd_

geometry_msgs::Twist velocity_controller::ControllerNode::cmd_
private

Definition at line 49 of file controller_node.h.

◆ command_subscriber

ros::Subscriber velocity_controller::ControllerNode::command_subscriber
private

Definition at line 48 of file local_controller_node.h.

◆ ctrl_state_

tuw_nav_msgs::ControllerState velocity_controller::ControllerNode::ctrl_state_
private

Definition at line 50 of file controller_node.h.

◆ goal_r_

float velocity_controller::ControllerNode::goal_r_
private

Definition at line 39 of file controller_node.h.

◆ Kd_val_

float velocity_controller::ControllerNode::Kd_val_
private

Definition at line 42 of file controller_node.h.

◆ Ki_val_

float velocity_controller::ControllerNode::Ki_val_
private

Definition at line 41 of file controller_node.h.

◆ Kp_val_

float velocity_controller::ControllerNode::Kp_val_
private

Definition at line 40 of file controller_node.h.

◆ last_update_

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

Definition at line 43 of file controller_node.h.

◆ max_vel_v_

float velocity_controller::ControllerNode::max_vel_v_
private

Definition at line 37 of file controller_node.h.

◆ max_vel_w_

float velocity_controller::ControllerNode::max_vel_w_
private

Definition at line 38 of file controller_node.h.

◆ n_

ros::NodeHandle velocity_controller::ControllerNode::n_

Node handler to the root node.

Definition at line 27 of file controller_node.h.

◆ n_param_

ros::NodeHandle velocity_controller::ControllerNode::n_param_

Node handler to the current node.

Definition at line 28 of file controller_node.h.

◆ pose_subscriber

ros::Subscriber velocity_controller::ControllerNode::pose_subscriber
private

Definition at line 47 of file local_controller_node.h.

◆ pubCmdVel_

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

Definition at line 32 of file controller_node.h.

◆ pubState_

ros::Publisher velocity_controller::ControllerNode::pubState_
private

Definition at line 33 of file controller_node.h.

◆ rate_

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

Definition at line 29 of file controller_node.h.

◆ state_publisher

ros::Publisher velocity_controller::ControllerNode::state_publisher
private

Definition at line 46 of file local_controller_node.h.

◆ subCtrl_

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

Definition at line 36 of file controller_node.h.

◆ subPath_

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

Definition at line 35 of file controller_node.h.

◆ subPose_

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

Definition at line 34 of file controller_node.h.

◆ twist_publisher

ros::Publisher velocity_controller::ControllerNode::twist_publisher
private

Definition at line 45 of file local_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 Feb 28 2022 23:57:38