local_controller_node.cpp
Go to the documentation of this file.
2 
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  name = argv[1];
13  }
14  ros::init(argc, argv, argv[1]);
16 
18 
19  ros::spin();
20  return 0;
21 }
22 
23 namespace velocity_controller {
25  n_(n),
26  n_param_("~"),
27  action_server(n, "execute_path", [&](const auto& goal) {this->onGoalReceived(goal);}, false)
28  {
29  twist_publisher = n.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
30  state_publisher = n.advertise<tuw_nav_msgs::ControllerState>("state_trajectory_ctrl", 10);
31  pose_subscriber = n.subscribe("pose", 1000, &ControllerNode::onPoseReceived, this);
32  command_subscriber = n.subscribe("ctrl", 1000, &ControllerNode::onCommandReceived, this);
33  action_server.start();
34  }
35 
36  void ControllerNode::onPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose){
37  PathPoint pt;
38  pt.x = pose->pose.pose.position.x;
39  pt.y = pose->pose.pose.position.y;
40 
41  tf::Quaternion q(pose->pose.pose.orientation.x, pose->pose.pose.orientation.y, pose->pose.pose.orientation.z,
42  pose->pose.pose.orientation.w);
43  tf::Matrix3x3 m(q);
44  double roll, pitch, yaw;
45  m.getRPY(roll, pitch, yaw);
46 
47  pt.theta = yaw;
48 
49  ros::Time time = ros::Time::now();
50  ros::Duration d = time - last_update_;
51 
52  float delta_t = d.sec + NSEC_2_SECS(d.nsec);
53  update(pt, delta_t);
54 
55  float v, w;
56  getSpeed(&v, &w);
57  geometry_msgs::Twist command;
58  command.linear.x = v;
59  command.angular.z = w;
60  twist_publisher.publish(command);
61  }
62 
63  void ControllerNode::publishControllerState(const nav_msgs::Path &path) {
64  tuw_nav_msgs::ControllerState controller_state;
65  controller_state.progress_in_relation_to = path.header.seq;
66  controller_state.header.frame_id = path.header.frame_id;
67  controller_state.header.stamp = ros::Time::now();
68  controller_state.progress = getProgress();
69  if (isActive()) {
70  controller_state.state = controller_state.STATE_DRIVING;
71  } else {
72  controller_state.state = controller_state.STATE_IDLE;
73  }
74  state_publisher.publish(controller_state);
75  }
76 
77  void ControllerNode::onCommandReceived(const std_msgs::String command){
78  std::string s = command.data;
79 
80  ROS_INFO("Multi Robot Controller: received %s", s.c_str());
81  if (s.compare("run") == 0) {
82  setState(run);
83  } else if (s.compare("stop") == 0) {
84  setState(stop);
85  } else if (s.compare("step") == 0) {
86  setState(step);
87  } else {
88  setState(run);
89  }
90  }
91 
92  void ControllerNode::onGoalReceived(const tuw_local_controller_msgs::ExecutePathGoalConstPtr &goal) {
93 
94  const auto& path = goal->path;
95  if (path.poses.empty()) {
96  return;
97  }
98 
99  ControllerConfig config;
100  n_param_.getParam("max_v",config.max_v);
101  n_param_.getParam("max_w", config.max_w);
102  n_param_.getParam("goal_radius", config.goal_radius);
103  n_param_.getParam("Kp", config.Kp);;
104  n_param_.getParam("Ki", config.Ki);
105  n_param_.getParam("Kd", config.Kd);
106  setSpeedParams(config.max_v, config.max_w);
107  setGoalRadius(config.goal_radius);
108  setPID(config.Kp, config.Ki, config.Kd);
109 
110  setupController(path, config);
111 
112  tuw_local_controller_msgs::ExecutePathResult result;
113  geometry_msgs::Pose pose;
114  result.pose = pose;
115 
116  ros::Rate rate(5);
117  int progress = getProgress();
118  bool success = true;
119 
120  while (progress < goal->path.poses.size()) {
121  if (action_server.isPreemptRequested() || !ros::ok()) {
122  ROS_INFO("Goal preempted.");
123  action_server.setPreempted(result);
124  success = false;
125  break;
126  }
127 
128  tuw_local_controller_msgs::ExecutePathFeedback feedback;
129  feedback.current_step = progress;
130  action_server.publishFeedback(feedback);
131  publishControllerState(path);
132  rate.sleep();
133  progress = getProgress();
134  }
135 
136  if (success) {
137  action_server.setSucceeded(result, "Robot finished path.");
138  }
139  }
140 
141  void ControllerNode::setupController(const nav_msgs::Path &path, const ControllerConfig& config) {
142 
143  auto it = path.poses.begin();
144  std::vector<PathPoint> path_points;
145  for (; it != path.poses.end(); ++it)
146  {
147  PathPoint pt;
148 
149  tf::Quaternion q(it->pose.orientation.x, it->pose.orientation.y, it->pose.orientation.z, it->pose.orientation.w);
150  tf::Matrix3x3 m(q);
151  double roll, pitch, yaw;
152  m.getRPY(roll, pitch, yaw);
153 
154  pt.x = it->pose.position.x;
155  pt.y = it->pose.position.y;
156  pt.theta = yaw;
157 
158  path_points.push_back(pt);
159  }
160 
161  setSpeedParams(config.max_v, config.max_w);
162  setGoalRadius(config.goal_radius);
163  setPID(config.Kp, config.Ki, config.Kd);
164  setPath(std::make_shared<std::vector<PathPoint>>(path_points));
165  }
166 }
tf::Matrix3x3
velocity_controller::ControllerConfig::Kp
float Kp
Definition: local_controller_node.h:25
local_controller_node.h
velocity_controller::ControllerConfig::Ki
float Ki
Definition: local_controller_node.h:26
velocity_controller::ControllerConfig::Kd
float Kd
Definition: local_controller_node.h:27
velocity_controller::Point_t::x
float x
Definition: controller.h:15
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
s
XmlRpcServer s
NSEC_2_SECS
#define NSEC_2_SECS(A)
Definition: local_controller_node.cpp:6
velocity_controller::Point_t::y
float y
Definition: controller.h:16
command
ROSLIB_DECL std::string command(const std::string &cmd)
velocity_controller::Point_t::theta
float theta
Definition: controller.h:17
step
unsigned int step
velocity_controller::ControllerConfig::goal_radius
float goal_radius
Definition: local_controller_node.h:24
velocity_controller::ControllerNode
Definition: controller_node.h:16
ros::ok
ROSCPP_DECL bool ok()
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
velocity_controller::stop
@ stop
Definition: controller.h:25
velocity_controller
Definition: controller.h:11
velocity_controller::run
@ run
Definition: controller.h:24
d
d
velocity_controller::ControllerConfig::max_w
float max_w
Definition: local_controller_node.h:23
velocity_controller::ControllerConfig
Definition: local_controller_node.h:21
velocity_controller::ControllerNode::ControllerNode
ControllerNode(ros::NodeHandle &n)
Construct a new Controller Node object.
Definition: controller_node.cpp:26
velocity_controller::ControllerConfig::max_v
float max_v
Definition: local_controller_node.h:22
ros::Rate::sleep
bool sleep()
velocity_controller::Point_t
Definition: controller.h:13
transform_datatypes.h
ros::Time
ros::Rate
ros::spin
ROSCPP_DECL void spin()
main
int main(int argc, char **argv)
Definition: local_controller_node.cpp:8
ROS_INFO
#define ROS_INFO(...)
ros::Duration
tf::Quaternion
ros::NodeHandle
ros::Time::now
static Time now()


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