35 #include "dwb_plugins/standard_traj_generator.hpp"
40 #include "dwb_plugins/xy_theta_iterator.hpp"
41 #include "nav_2d_utils/parameters.hpp"
42 #include "pluginlib/class_list_macros.hpp"
43 #include "dwb_core/exceptions.hpp"
44 #include "nav2_util/node_utils.hpp"
50 const nav2_util::LifecycleNode::SharedPtr & nh,
51 const std::string & plugin_name)
54 kinematics_handler_ = std::make_shared<KinematicsHandler>();
58 nav2_util::declare_parameter_if_not_declared(
60 plugin_name +
".sim_time", rclcpp::ParameterValue(1.7));
61 nav2_util::declare_parameter_if_not_declared(
63 plugin_name +
".discretize_by_time", rclcpp::ParameterValue(
false));
65 nav2_util::declare_parameter_if_not_declared(
67 plugin_name +
".time_granularity", rclcpp::ParameterValue(0.5));
68 nav2_util::declare_parameter_if_not_declared(
70 plugin_name +
".linear_granularity", rclcpp::ParameterValue(0.5));
71 nav2_util::declare_parameter_if_not_declared(
73 plugin_name +
".angular_granularity", rclcpp::ParameterValue(0.025));
74 nav2_util::declare_parameter_if_not_declared(
76 plugin_name +
".include_last_point", rclcpp::ParameterValue(
true));
78 nav2_util::declare_parameter_if_not_declared(
80 plugin_name +
".limit_vel_cmd_in_traj", rclcpp::ParameterValue(
false));
90 nh->get_parameter(plugin_name +
".sim_time", sim_time_);
91 nh->get_parameter(plugin_name +
".discretize_by_time", discretize_by_time_);
95 nh->get_parameter(plugin_name +
".include_last_point", include_last_point_);
100 const nav2_util::LifecycleNode::SharedPtr & nh)
102 velocity_iterator_ = std::make_shared<XYThetaIterator>();
103 velocity_iterator_->initialize(nh, kinematics_handler_,
plugin_name_);
107 const nav_2d_msgs::msg::Twist2D & current_velocity)
109 velocity_iterator_->startNewIteration(current_velocity, sim_time_);
114 return velocity_iterator_->hasMoreTwists();
119 return velocity_iterator_->nextTwist();
123 const nav_2d_msgs::msg::Twist2D & cmd_vel)
125 std::vector<double> steps;
126 if (discretize_by_time_) {
129 double vmag = hypot(cmd_vel.x, cmd_vel.y);
132 double projected_linear_distance = vmag * sim_time_;
135 double projected_angular_distance = fabs(cmd_vel.theta) * sim_time_;
138 int num_steps = ceil(
142 steps.resize(num_steps);
144 if (steps.size() == 0) {
147 std::fill(steps.begin(), steps.end(), sim_time_ / steps.size());
152 const geometry_msgs::msg::Pose2D & start_pose,
153 const nav_2d_msgs::msg::Twist2D & start_vel,
154 const nav_2d_msgs::msg::Twist2D & cmd_vel)
156 dwb_msgs::msg::Trajectory2D traj;
157 traj.velocity = cmd_vel;
159 geometry_msgs::msg::Pose2D pose = start_pose;
160 nav_2d_msgs::msg::Twist2D vel = start_vel;
161 double running_time = 0.0;
163 traj.poses.push_back(start_pose);
164 bool first_vel =
false;
165 for (
double dt : steps) {
176 traj.poses.push_back(pose);
177 traj.time_offsets.push_back(rclcpp::Duration::from_seconds(running_time));
181 if (include_last_point_) {
182 traj.poses.push_back(pose);
183 traj.time_offsets.push_back(rclcpp::Duration::from_seconds(running_time));
193 const nav_2d_msgs::msg::Twist2D & cmd_vel,
194 const nav_2d_msgs::msg::Twist2D & start_vel,
const double dt)
197 nav_2d_msgs::msg::Twist2D new_vel;
198 new_vel.x = projectVelocity(
199 start_vel.x, kinematics.getAccX(),
200 kinematics.getDecelX(), dt, cmd_vel.x);
201 new_vel.y = projectVelocity(
202 start_vel.y, kinematics.getAccY(),
203 kinematics.getDecelY(), dt, cmd_vel.y);
204 new_vel.theta = projectVelocity(
206 kinematics.getAccTheta(), kinematics.getDecelTheta(),
212 const geometry_msgs::msg::Pose2D start_pose,
213 const nav_2d_msgs::msg::Twist2D & vel,
const double dt)
215 geometry_msgs::msg::Pose2D new_pose;
216 new_pose.x = start_pose.x +
217 (vel.x * cos(start_pose.theta) + vel.y * cos(M_PI_2 + start_pose.theta)) * dt;
218 new_pose.y = start_pose.y +
219 (vel.x * sin(start_pose.theta) + vel.y * sin(M_PI_2 + start_pose.theta)) * dt;
220 new_pose.theta = start_pose.theta + vel.theta * dt;
226 PLUGINLIB_EXPORT_CLASS(
Interface for iterating through possible velocities and creating trajectories.
Standard DWA-like trajectory generator.
void startNewIteration(const nav_2d_msgs::msg::Twist2D ¤t_velocity) override
Start a new iteration based on the current velocity.
double angular_granularity_
If not discretizing by time, the amount of angular space between points.
virtual nav_2d_msgs::msg::Twist2D computeNewVelocity(const nav_2d_msgs::msg::Twist2D &cmd_vel, const nav_2d_msgs::msg::Twist2D &start_vel, const double dt)
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
std::string plugin_name_
the name of the overlying plugin ID
bool hasMoreTwists() override
Test to see whether there are more twists to test.
virtual std::vector< double > getTimeSteps(const nav_2d_msgs::msg::Twist2D &cmd_vel)
Compute an array of time deltas between the points in the generated trajectory.
bool limit_vel_cmd_in_traj_
Option to limit velocity in the trajectory generator by using current velocity.
double linear_granularity_
If not discretizing by time, the amount of linear space between points.
void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.
dwb_msgs::msg::Trajectory2D generateTrajectory(const geometry_msgs::msg::Pose2D &start_pose, const nav_2d_msgs::msg::Twist2D &start_vel, const nav_2d_msgs::msg::Twist2D &cmd_vel) override
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.
virtual geometry_msgs::msg::Pose2D computeNewPosition(const geometry_msgs::msg::Pose2D start_pose, const nav_2d_msgs::msg::Twist2D &vel, const double dt)
Use the robot's kinematic model to predict new positions for the robot.
virtual void initializeIterator(const nav2_util::LifecycleNode::SharedPtr &nh)
Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
nav_2d_msgs::msg::Twist2D nextTwist() override
Return the next twist and advance the iteration.
A struct containing one representation of the robot's kinematics.