controller.h
Go to the documentation of this file.
1 #ifndef CONTROLLER_H
2 #define CONTROLLER_H
3 
4 // ROS
5 #include <ros/ros.h>
6 #include <geometry_msgs/Twist.h>
7 #include <nav_msgs/Odometry.h>
8 #include <nav_msgs/Path.h>
9 #include <tuw_multi_robot_msgs/RobotInfo.h>
10 
12 {
13 typedef struct Point_t
14 {
15  float x = 0;
16  float y = 0;
17  float theta = 0;
18 } PathPoint;
19 
20 
21 
22 typedef enum state_t
23 {
24  run,
28 } state;
29 
31 {
32 
33 public:
38  Controller();
44  void setPath(std::shared_ptr<std::vector<PathPoint>> _path);
51  void update(PathPoint _odom, float _delta_t);
58  void setSpeedParams(float _max_v, float _max_w);
65  void getSpeed(float *_v, float *_w);
71  void setGoalRadius(float _r);
79  void setPID(float _Kp, float _Ki, float _Kd);
85  void setState(state s);
90  size_t getProgress();
95  bool isActive();
96 
97  int getStatus();
98  void setGoodId(int);
99  int getGoodId();
100  void setOrderId(int);
101  int getOrderId();
102  void setOrderStatus(int);
103  int getOrderStatus();
104 
105 private:
106  float normalizeAngle(float _angle);
107  float absolute(float _val);
108  bool checkGoal(PathPoint _odom);
109  std::vector<PathPoint> path_;
111  float max_v_, max_w_;
112  float v_, w_;
113  bool plan_active = false;
114  float e_last_ = 0;
115  float e_dot_ = 0;
116  float Kp_ = 5;
117  float Kd_ = 1;
118  float Ki_ = 0.0;
119 
120  int robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_STOPPED;
121  int goodId;
122  int orderId;
124 
125  float goal_radius_ = 0.25;
126 
128 
129 protected:
131 };
132 
133 } // namespace velocity_controller
134 
135 #endif // CONTROLLER_NODE_H
velocity_controller::Controller::path_
std::vector< PathPoint > path_
Definition: controller.h:109
velocity_controller::Controller::normalizeAngle
float normalizeAngle(float _angle)
Definition: controller.cpp:133
velocity_controller::Controller::max_v_
float max_v_
Definition: controller.h:111
velocity_controller::Controller::setGoalRadius
void setGoalRadius(float _r)
Set the Goal Radius.
Definition: controller.cpp:22
velocity_controller::Point_t::x
float x
Definition: controller.h:15
velocity_controller::Controller::setState
void setState(state s)
Set the State (run stop step wait_step)
Definition: controller.cpp:69
velocity_controller::step
@ step
Definition: controller.h:26
velocity_controller::Controller::plan_active
bool plan_active
Definition: controller.h:113
velocity_controller::Controller::max_w_
float max_w_
Definition: controller.h:111
velocity_controller::Controller::robot_status
int robot_status
Definition: controller.h:120
s
XmlRpcServer s
velocity_controller::Controller::goodId
int goodId
Definition: controller.h:121
velocity_controller::Controller::w_
float w_
Definition: controller.h:112
ros.h
velocity_controller::Controller::e_last_
float e_last_
Definition: controller.h:114
velocity_controller::Point_t::y
float y
Definition: controller.h:16
velocity_controller::Point_t::theta
float theta
Definition: controller.h:17
velocity_controller::Controller::orderId
int orderId
Definition: controller.h:122
velocity_controller::Controller::checkGoal
bool checkGoal(PathPoint _odom)
Definition: controller.cpp:27
velocity_controller::Controller::update
void update(PathPoint _odom, float _delta_t)
updates the controller with the current robot position
Definition: controller.cpp:74
velocity_controller::Controller::getOrderId
int getOrderId()
velocity_controller::Controller::actual_cmd_
state actual_cmd_
Definition: controller.h:127
velocity_controller::Controller::v_
float v_
Definition: controller.h:112
velocity_controller::Controller::Controller
Controller()
Construct a new Controller object.
Definition: controller.cpp:8
velocity_controller::Controller::getSpeed
void getSpeed(float *_v, float *_w)
Returns the current speed values.
Definition: controller.cpp:152
velocity_controller::Controller::setOrderId
void setOrderId(int)
Definition: controller.cpp:163
velocity_controller::stop
@ stop
Definition: controller.h:25
velocity_controller
Definition: controller.h:11
velocity_controller::run
@ run
Definition: controller.h:24
velocity_controller::Controller::getProgress
size_t getProgress()
return progress,
Definition: controller.cpp:61
velocity_controller::state_t
state_t
Definition: controller.h:22
velocity_controller::Controller::Ki_
float Ki_
Definition: controller.h:118
velocity_controller::Controller::absolute
float absolute(float _val)
Definition: controller.cpp:125
velocity_controller::Controller::current_pose_
PathPoint current_pose_
Definition: controller.h:130
velocity_controller::state
enum velocity_controller::state_t state
velocity_controller::wait_step
@ wait_step
Definition: controller.h:27
velocity_controller::Controller::setPID
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
Definition: controller.cpp:54
velocity_controller::Controller::idx_path_target_point_
size_t idx_path_target_point_
Definition: controller.h:110
velocity_controller::Controller::Kp_
float Kp_
Definition: controller.h:116
velocity_controller::Controller::Kd_
float Kd_
Definition: controller.h:117
velocity_controller::Controller::getGoodId
int getGoodId()
Definition: controller.cpp:172
velocity_controller::Point_t
Definition: controller.h:13
velocity_controller::Controller::setOrderStatus
void setOrderStatus(int)
Definition: controller.cpp:176
velocity_controller::Controller::setGoodId
void setGoodId(int)
Definition: controller.cpp:167
velocity_controller::Controller::getOrderStatus
int getOrderStatus()
Definition: controller.cpp:180
velocity_controller::Controller::goal_radius_
float goal_radius_
Definition: controller.h:125
velocity_controller::PathPoint
struct velocity_controller::Point_t PathPoint
velocity_controller::Controller::setPath
void setPath(std::shared_ptr< std::vector< PathPoint >> _path)
Set the path the contorler has to follow.
Definition: controller.cpp:15
velocity_controller::Controller::e_dot_
float e_dot_
Definition: controller.h:115
velocity_controller::Controller::setSpeedParams
void setSpeedParams(float _max_v, float _max_w)
Set the Speed Params of the controller.
Definition: controller.cpp:146
velocity_controller::Controller::getStatus
int getStatus()
Definition: controller.cpp:158
velocity_controller::Controller
Definition: controller.h:30
velocity_controller::Controller::orderStatus
int orderStatus
Definition: controller.h:123
velocity_controller::Controller::isActive
bool isActive()
return progress, passed waypoints on the given path
Definition: controller.cpp:65


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:09:58