Go to the documentation of this file.
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>
44 void setPath(std::shared_ptr<std::vector<PathPoint>> _path);
79 void setPID(
float _Kp,
float _Ki,
float _Kd);
135 #endif // CONTROLLER_NODE_H
std::vector< PathPoint > path_
float normalizeAngle(float _angle)
void setGoalRadius(float _r)
Set the Goal Radius.
void setState(state s)
Set the State (run stop step wait_step)
bool checkGoal(PathPoint _odom)
void update(PathPoint _odom, float _delta_t)
updates the controller with the current robot position
Controller()
Construct a new Controller object.
void getSpeed(float *_v, float *_w)
Returns the current speed values.
size_t getProgress()
return progress,
float absolute(float _val)
enum velocity_controller::state_t state
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
size_t idx_path_target_point_
struct velocity_controller::Point_t PathPoint
void setPath(std::shared_ptr< std::vector< PathPoint >> _path)
Set the path the contorler has to follow.
void setSpeedParams(float _max_v, float _max_w)
Set the Speed Params of the controller.
bool isActive()
return progress, passed waypoints on the given path