Go to the documentation of this file.
3 #include <tuw_nav_msgs/ControllerState.h>
6 #define NSEC_2_SECS(A) ((float)A / 1000000000.0)
8 int main(
int argc,
char** argv)
10 std::string name(
"pid_controller");
71 pt.
x = _pose->pose.pose.position.x;
72 pt.
y = _pose->pose.pose.position.y;
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);
77 double roll, pitch, yaw;
78 m.
getRPY(roll, pitch, yaw);
111 ctrl_state_.progress_in_relation_to = _path->header.seq;
112 ctrl_state_.header.frame_id = _path->header.frame_id;
114 if (_path->poses.size() == 0)
121 float nearest_dist = std::numeric_limits<float>::max();
124 auto it = _path->poses.begin();
143 std::vector<PathPoint> path;
144 for (; it != _path->poses.end(); ++it)
148 tf::Quaternion q(it->pose.orientation.x, it->pose.orientation.y, it->pose.orientation.z, it->pose.orientation.w);
150 double roll, pitch, yaw;
151 m.
getRPY(roll, pitch, yaw);
153 pt.
x = it->pose.position.x;
154 pt.
y = it->pose.position.y;
160 setPath(std::make_shared<std::vector<PathPoint>>(path));
165 std::string
s = _cmd.data;
167 ROS_INFO(
"Multi Robot Controller: received %s",
s.c_str());
168 if (
s.compare(
"run") == 0)
172 else if (
s.compare(
"stop") == 0)
176 else if (
s.compare(
"step") == 0)
void setGoalRadius(float _r)
Set the Goal Radius.
void setState(state s)
Set the State (run stop step wait_step)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
bool getParam(const std::string &key, bool &b) const
void subCtrlCb(const std_msgs::String _cmd)
ROSCPP_DECL void spinOnce()
geometry_msgs::Twist cmd_
void subPathCb(const nav_msgs::Path::ConstPtr &_path)
void update(PathPoint _odom, float _delta_t)
updates the controller with the current robot position
ros::NodeHandle n_param_
Node handler to the current node.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void getSpeed(float *_v, float *_w)
Returns the current speed values.
size_t getProgress()
return progress,
ControllerNode(ros::NodeHandle &n)
Construct a new Controller Node object.
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())
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
int main(int argc, char **argv)
void subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
void setPath(std::shared_ptr< std::vector< PathPoint >> _path)
Set the path the contorler has to follow.
T param(const std::string ¶m_name, const T &default_val) const
void setSpeedParams(float _max_v, float _max_w)
Set the Speed Params of the controller.
ros::Publisher pubCmdVel_
bool isActive()
return progress, passed waypoints on the given path
tuw_nav_msgs::ControllerState ctrl_state_