#include <controller_node.h>
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::Rate > | rate_ |
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_ |
Definition at line 15 of file controller_node.h.
velocity_controller::ControllerNode::ControllerNode | ( | ros::NodeHandle & | n | ) |
Construct a new Controller Node object.
n | the node handle to subscribe topics |
Definition at line 33 of file controller_node.cpp.
|
private |
Definition at line 157 of file controller_node.cpp.
|
private |
Definition at line 106 of file controller_node.cpp.
|
private |
Definition at line 76 of file controller_node.cpp.
|
private |
Definition at line 41 of file controller_node.h.
|
private |
Definition at line 44 of file controller_node.h.
|
private |
Definition at line 43 of file controller_node.h.
|
private |
Definition at line 42 of file controller_node.h.
|
private |
Definition at line 45 of file controller_node.h.
|
private |
Definition at line 39 of file controller_node.h.
|
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.
|
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.
|
private |
Definition at line 34 of file controller_node.h.
|
private |
Definition at line 33 of file controller_node.h.
|
private |
Definition at line 32 of file controller_node.h.
|
private |
Definition at line 35 of file controller_node.h.
|
private |
Definition at line 38 of file controller_node.h.
|
private |
Definition at line 37 of file controller_node.h.
|
private |
Definition at line 36 of file controller_node.h.