52 kinematics_ = std::make_shared<KinematicParameters>();
90 nh.
param(
"use_dwa", use_dwa,
false);
94 "Please use LimitedAccelGenerator for that functionality.");
115 std::vector<double> steps;
122 double vmag = hypot(cmd_vel.x, cmd_vel.y);
125 double projected_linear_distance = vmag *
sim_time_;
128 double projected_angular_distance = fabs(cmd_vel.theta) *
sim_time_;
133 steps.resize(num_steps);
135 if (steps.size() == 0)
139 std::fill(steps.begin(), steps.end(),
sim_time_ / steps.size());
144 const nav_2d_msgs::Twist2D& start_vel,
145 const nav_2d_msgs::Twist2D& cmd_vel)
147 dwb_msgs::Trajectory2D traj;
148 traj.velocity = cmd_vel;
151 geometry_msgs::Pose2D pose = start_pose;
152 nav_2d_msgs::Twist2D vel = start_vel;
153 double running_time = 0.0;
155 for (
double dt : steps)
157 traj.poses.push_back(pose);
169 traj.poses.push_back(pose);
180 const nav_2d_msgs::Twist2D& start_vel,
const double dt)
182 nav_2d_msgs::Twist2D new_vel;
191 const nav_2d_msgs::Twist2D& vel,
const double dt)
193 geometry_msgs::Pose2D new_pose;
194 new_pose.x = start_pose.x + (vel.x * cos(start_pose.theta) + vel.y * cos(M_PI_2 + start_pose.theta)) * dt;
195 new_pose.y = start_pose.y + (vel.x * sin(start_pose.theta) + vel.y * sin(M_PI_2 + start_pose.theta)) * dt;
196 new_pose.theta = start_pose.theta + vel.theta * dt;