controller_node.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <tuw_nav_msgs/ControllerState.h>
5 
6 #define NSEC_2_SECS(A) ((float)A / 1000000000.0)
7 
8 int main(int argc, char** argv)
9 {
10  std::string name("pid_controller");
11  if (argc >= 2)
12  {
13  name = argv[1];
14  }
15  ros::init(argc, argv, argv[1]);
17 
19 
20 
21  return 0;
22 }
23 
24 namespace velocity_controller
25 {
27 {
28  max_vel_v_ = 0.8;
29  n_param_.getParam("max_v", max_vel_v_);
30 
31  max_vel_w_ = 1.0;
32  n_param_.getParam("max_w", max_vel_w_);
34 
35  goal_r_ = 0.2;
36  n_param_.getParam("goal_radius", goal_r_);
38 
39  Kp_val_ = 5.0;
40  n_param_.getParam("Kp", Kp_val_);
41 
42  Ki_val_ = 0.0;
43  n_param_.getParam("Ki", Ki_val_);
44 
45  Kd_val_ = 1.0;
46  n_param_.getParam("Kd", Kd_val_);
48 
49  double loop_rate;
50  n_param_.param<double>("loop_rate", loop_rate, 5);
51 
52  pubCmdVel_ = n.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
53  pubState_ = n.advertise<tuw_nav_msgs::ControllerState>("state_trajectory_ctrl", 10);
54  subPose_ = n.subscribe("pose", 1000, &ControllerNode::subPoseCb, this);
55  subPath_ = n.subscribe("path", 1000, &ControllerNode::subPathCb, this);
56  subCtrl_ = n.subscribe("ctrl", 1000, &ControllerNode::subCtrlCb, this);
57 
58  ros::Rate r(loop_rate);
59 
60  while (ros::ok())
61  {
62  ros::spinOnce();
63  publishState();
64  r.sleep();
65  }
66 }
67 
68 void ControllerNode::subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
69 {
70  PathPoint pt;
71  pt.x = _pose->pose.pose.position.x;
72  pt.y = _pose->pose.pose.position.y;
73 
74  tf::Quaternion q(_pose->pose.pose.orientation.x, _pose->pose.pose.orientation.y, _pose->pose.pose.orientation.z,
75  _pose->pose.pose.orientation.w);
76  tf::Matrix3x3 m(q);
77  double roll, pitch, yaw;
78  m.getRPY(roll, pitch, yaw);
79 
80  pt.theta = yaw;
81 
82  ros::Time time = ros::Time::now();
83  ros::Duration d = time - last_update_;
84 
85  float delta_t = d.sec + NSEC_2_SECS(d.nsec);
86  update(pt, delta_t);
87 
88 
89  float v, w;
90  getSpeed(&v, &w);
91  cmd_.linear.x = v;
92  cmd_.angular.z = w;
93 
94 
96 }
97 
99  ctrl_state_.header.stamp = ros::Time::now();
100  ctrl_state_.progress = getProgress();
101  if(isActive()) {
102  ctrl_state_.state = ctrl_state_.STATE_DRIVING;
103  } else {
104  ctrl_state_.state = ctrl_state_.STATE_IDLE;
105  }
107 }
108 
109 void ControllerNode::subPathCb(const nav_msgs::Path_<std::allocator<void>>::ConstPtr& _path)
110 {
111  ctrl_state_.progress_in_relation_to = _path->header.seq;
112  ctrl_state_.header.frame_id = _path->header.frame_id;
113 
114  if (_path->poses.size() == 0)
115  return;
116 
117  // start at nearest point on path to pose
118  // behavior controller resends full paths, therefore
119  // it is important to start from the robots location
120 
121  float nearest_dist = std::numeric_limits<float>::max();
122  float dist = 0;
123 
124  auto it = _path->poses.begin();
125  /*
126  bool changed = true;
127 
128  while (it != _path->poses.end() && changed)
129  {
130  dist = pow(current_pose_.x - it->pose.position.x, 2) + pow(current_pose_.y - it->pose.position.y, 2);
131  if (dist < nearest_dist)
132  {
133  nearest_dist = dist;
134  changed = true;
135  it++;
136  }
137  else
138  {
139  changed = false;
140  }
141  }*/
142 
143  std::vector<PathPoint> path;
144  for (; it != _path->poses.end(); ++it)
145  {
146  PathPoint pt;
147 
148  tf::Quaternion q(it->pose.orientation.x, it->pose.orientation.y, it->pose.orientation.z, it->pose.orientation.w);
149  tf::Matrix3x3 m(q);
150  double roll, pitch, yaw;
151  m.getRPY(roll, pitch, yaw);
152 
153  pt.x = it->pose.position.x;
154  pt.y = it->pose.position.y;
155  pt.theta = yaw;
156 
157  path.push_back(pt);
158  }
159 
160  setPath(std::make_shared<std::vector<PathPoint>>(path));
161 }
162 
163 void ControllerNode::subCtrlCb(const std_msgs::String _cmd)
164 {
165  std::string s = _cmd.data;
166 
167  ROS_INFO("Multi Robot Controller: received %s", s.c_str());
168  if (s.compare("run") == 0)
169  {
170  setState(run);
171  }
172  else if (s.compare("stop") == 0)
173  {
174  setState(stop);
175  }
176  else if (s.compare("step") == 0)
177  {
178  setState(step);
179  }
180  else
181  {
182  setState(run);
183  }
184 }
185 }
tf::Matrix3x3
velocity_controller::ControllerNode::subPose_
ros::Subscriber subPose_
Definition: controller_node.h:34
velocity_controller::ControllerNode::pubState_
ros::Publisher pubState_
Definition: controller_node.h:33
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
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tf::Matrix3x3::getRPY
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
velocity_controller::ControllerNode::max_vel_w_
float max_vel_w_
Definition: controller_node.h:38
s
XmlRpcServer s
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
velocity_controller::Point_t::y
float y
Definition: controller.h:16
velocity_controller::ControllerNode::publishState
void publishState()
Definition: controller_node.cpp:98
velocity_controller::Point_t::theta
float theta
Definition: controller.h:17
velocity_controller::ControllerNode::subCtrlCb
void subCtrlCb(const std_msgs::String _cmd)
Definition: controller_node.cpp:163
ros::spinOnce
ROSCPP_DECL void spinOnce()
velocity_controller::ControllerNode::cmd_
geometry_msgs::Twist cmd_
Definition: controller_node.h:49
velocity_controller::ControllerNode::subPathCb
void subPathCb(const nav_msgs::Path::ConstPtr &_path)
Definition: controller_node.cpp:109
velocity_controller::ControllerNode::Kd_val_
float Kd_val_
Definition: controller_node.h:42
controller_node.h
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::ControllerNode::n_param_
ros::NodeHandle n_param_
Node handler to the current node.
Definition: controller_node.h:28
NSEC_2_SECS
#define NSEC_2_SECS(A)
Definition: controller_node.cpp:6
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
velocity_controller::ControllerNode
Definition: controller_node.h:16
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
std::allocator
velocity_controller::ControllerNode::max_vel_v_
float max_vel_v_
Definition: controller_node.h:37
velocity_controller::ControllerNode::Ki_val_
float Ki_val_
Definition: controller_node.h:41
velocity_controller::Controller::getSpeed
void getSpeed(float *_v, float *_w)
Returns the current speed values.
Definition: controller.cpp:152
velocity_controller::ControllerNode::Kp_val_
float Kp_val_
Definition: controller_node.h:40
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
d
d
velocity_controller::ControllerNode::ControllerNode
ControllerNode(ros::NodeHandle &n)
Construct a new Controller Node object.
Definition: controller_node.cpp:26
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
velocity_controller::ControllerNode::subPath_
ros::Subscriber subPath_
Definition: controller_node.h:35
ros::Rate::sleep
bool sleep()
velocity_controller::Controller::setPID
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
Definition: controller.cpp:54
main
int main(int argc, char **argv)
Definition: controller_node.cpp:8
velocity_controller::Point_t
Definition: controller.h:13
transform_datatypes.h
ros::Time
velocity_controller::ControllerNode::subPoseCb
void subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
Definition: controller_node.cpp:68
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
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Rate
velocity_controller::ControllerNode::goal_r_
float goal_r_
Definition: controller_node.h:39
velocity_controller::ControllerNode::subCtrl_
ros::Subscriber subCtrl_
Definition: controller_node.h:36
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
Definition: controller.h:30
ROS_INFO
#define ROS_INFO(...)
velocity_controller::ControllerNode::pubCmdVel_
ros::Publisher pubCmdVel_
Definition: controller_node.h:32
ros::Duration
velocity_controller::Controller::isActive
bool isActive()
return progress, passed waypoints on the given path
Definition: controller.cpp:65
tf::Quaternion
velocity_controller::ControllerNode::ctrl_state_
tuw_nav_msgs::ControllerState ctrl_state_
Definition: controller_node.h:50
ros::NodeHandle
ros::Time::now
static Time now()
velocity_controller::ControllerNode::last_update_
ros::Time last_update_
Definition: controller_node.h:43


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