segment_controller.h
Go to the documentation of this file.
1 #ifndef SEGMENT_CONTROLLER_H
2 #define SEGMENT_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 
11 namespace velocity_controller
12 {
13 
14 typedef struct PathPrecondition_t
15 {
16  int robot;
19 
20 typedef struct PathPoint_t
21 {
22  float x;
23  float y;
24  float theta;
25  std::vector<PathPrecondition> precondition;
26 } PathPoint;
27 
28 typedef enum state_t
29 {
30  run,
31  stop,
32  step,
33  wait_step
34 } state;
35 
37 {
38 
39  public:
49  void setPath(std::shared_ptr<std::vector<PathPoint>> _path);
56  void update(PathPoint _odom, float _delta_t);
63  void setSpeedParams(float _max_v, float _max_w);
70  void getSpeed(float *_v, float *_w);
76  void setGoalRadius(float _r);
84  void setPID(float _Kp, float _Ki, float _Kd);
90  void setState(state s);
102  int getCount();
103 
104  int getStatus();
105  void setGoodId(int);
106  int getGoodId();
107  void setOrderId(int);
108  int getOrderId();
109  void setOrderStatus(int);
110  int getOrderStatus();
111 
112  bool getPlanActive() { return plan_active; }
113 
114  private:
116  float normalizeAngle(float _angle);
117  float absolute(float _val);
118  bool checkGoal(PathPoint _odom);
119  std::shared_ptr<std::vector<PathPoint>> path_;
120  float max_v_, max_w_;
121  float v_, w_;
122  int pathCounter_ = 0;
123  bool plan_active = false;
124  float e_last_ = 0;
125  float e_dot_ = 0;
126  float Kp_ = 5;
127  float Kd_ = 1;
128  float Ki_ = 0.0;
129  float goal_radius_ = 0.25;
130 
131  int robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_STOPPED;
132  int goodId;
133  int orderId;
135 
136  std::vector<int> actualPreconditions;
137 
139 };
140 
141 } // namespace velocity_controller
142 
143 #endif // CONTROLLER_NODE_H
velocity_controller::PathPrecondition_t::stepCondition
int stepCondition
Definition: segment_controller.h:17
velocity_controller::PathPrecondition_t::robot
int robot
Definition: segment_controller.h:16
velocity_controller::SegmentController::orderId
int orderId
Definition: segment_controller.h:133
velocity_controller::SegmentController::orderStatus
int orderStatus
Definition: segment_controller.h:134
velocity_controller::SegmentController::getGoodId
int getGoodId()
Definition: segment_controller.cpp:208
velocity_controller::SegmentController::absolute
float absolute(float _val)
Definition: segment_controller.cpp:156
velocity_controller::PathPoint_t::precondition
std::vector< PathPrecondition > precondition
Definition: segment_controller.h:25
velocity_controller::SegmentController::v_
float v_
Definition: segment_controller.h:121
velocity_controller::step
@ step
Definition: controller.h:26
velocity_controller::SegmentController::goodId
int goodId
Definition: segment_controller.h:132
velocity_controller::SegmentController::plan_active
bool plan_active
Definition: segment_controller.h:123
s
XmlRpcServer s
ros.h
velocity_controller::SegmentController::getOrderStatus
int getOrderStatus()
Definition: segment_controller.cpp:216
velocity_controller::SegmentController::getPlanActive
bool getPlanActive()
Definition: segment_controller.h:112
velocity_controller::SegmentController::setGoodId
void setGoodId(int)
Definition: segment_controller.cpp:203
velocity_controller::SegmentController::setPath
void setPath(std::shared_ptr< std::vector< PathPoint >> _path)
Set the path the contorler has to follow.
Definition: segment_controller.cpp:15
velocity_controller::PathPoint_t
Definition: segment_controller.h:20
velocity_controller::SegmentController::pathCounter_
int pathCounter_
Definition: segment_controller.h:122
velocity_controller::SegmentController::max_w_
float max_w_
Definition: segment_controller.h:120
velocity_controller::SegmentController::goal_radius_
float goal_radius_
Definition: segment_controller.h:129
velocity_controller::SegmentController::actualPreconditions
std::vector< int > actualPreconditions
Definition: segment_controller.h:136
velocity_controller::SegmentController::max_v_
float max_v_
Definition: segment_controller.h:120
velocity_controller::SegmentController::e_last_
float e_last_
Definition: segment_controller.h:124
velocity_controller::SegmentController::setOrderStatus
void setOrderStatus(int)
Definition: segment_controller.cpp:212
velocity_controller::PathPrecondition
struct velocity_controller::PathPrecondition_t PathPrecondition
velocity_controller::PathPoint_t::theta
float theta
Definition: segment_controller.h:24
velocity_controller::stop
@ stop
Definition: controller.h:25
velocity_controller
Definition: controller.h:11
velocity_controller::run
@ run
Definition: controller.h:24
velocity_controller::SegmentController::getSpeed
void getSpeed(float *_v, float *_w)
Returns the current speed values.
Definition: segment_controller.cpp:188
velocity_controller::SegmentController::getCount
int getCount()
Returns the checkpoint number the robot is in.
Definition: segment_controller.cpp:24
velocity_controller::SegmentController::setSpeedParams
void setSpeedParams(float _max_v, float _max_w)
Set the Speed Params of the controller.
Definition: segment_controller.cpp:182
velocity_controller::SegmentController::getStatus
int getStatus()
Definition: segment_controller.cpp:194
velocity_controller::state_t
state_t
Definition: controller.h:22
velocity_controller::SegmentController::setState
void setState(state s)
Set the State (run stop step wait_step)
Definition: segment_controller.cpp:100
velocity_controller::SegmentController::setPID
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
Definition: segment_controller.cpp:93
velocity_controller::SegmentController::actual_cmd_
state actual_cmd_
Definition: segment_controller.h:138
velocity_controller::state
enum velocity_controller::state_t state
velocity_controller::SegmentController::path_
std::shared_ptr< std::vector< PathPoint > > path_
Definition: segment_controller.h:119
velocity_controller::PathPrecondition_t
Definition: segment_controller.h:14
velocity_controller::SegmentController::update
void update(PathPoint _odom, float _delta_t)
updates the controller with the current robot position
Definition: segment_controller.cpp:106
velocity_controller::SegmentController::setOrderId
void setOrderId(int)
Definition: segment_controller.cpp:199
velocity_controller::wait_step
@ wait_step
Definition: controller.h:27
velocity_controller::Point_t
Definition: controller.h:13
velocity_controller::SegmentController::setGoalRadius
void setGoalRadius(float _r)
Set the Goal Radius.
Definition: segment_controller.cpp:30
velocity_controller::SegmentController::Kp_
float Kp_
Definition: segment_controller.h:126
velocity_controller::PathPoint
struct velocity_controller::Point_t PathPoint
velocity_controller::SegmentController::SegmentController
SegmentController()
Construct a new Segment Controller object.
Definition: segment_controller.cpp:9
velocity_controller::SegmentController::checkGoal
bool checkGoal(PathPoint _odom)
Definition: segment_controller.cpp:63
velocity_controller::SegmentController::checkPrecondition
bool checkPrecondition(PathPoint p)
Definition: segment_controller.cpp:44
velocity_controller::PathPoint_t::y
float y
Definition: segment_controller.h:23
velocity_controller::SegmentController::Ki_
float Ki_
Definition: segment_controller.h:128
velocity_controller::SegmentController
Definition: segment_controller.h:36
velocity_controller::SegmentController::e_dot_
float e_dot_
Definition: segment_controller.h:125
velocity_controller::SegmentController::Kd_
float Kd_
Definition: segment_controller.h:127
velocity_controller::SegmentController::updatePrecondition
void updatePrecondition(PathPrecondition pc)
updates the sync step of other robots
Definition: segment_controller.cpp:35
velocity_controller::PathPoint_t::x
float x
Definition: segment_controller.h:22
velocity_controller::SegmentController::normalizeAngle
float normalizeAngle(float _angle)
Definition: segment_controller.cpp:165
velocity_controller::SegmentController::robot_status
int robot_status
Definition: segment_controller.h:131
velocity_controller::SegmentController::w_
float w_
Definition: segment_controller.h:121
velocity_controller::SegmentController::getOrderId
int getOrderId()


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