Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

yujin_ocs/yocs_velocity_smoother/src/velocity_smoother_nodelet.cpp's velocity code #127

Open
lahyeon opened this issue Jul 4, 2017 · 2 comments

Comments

@lahyeon
Copy link

lahyeon commented Jul 4, 2017

yujin_ocs/yocs_velocity_smoother/src/velocity_smoother_nodelet.cpp's velocity code's

I do not understand the calculation in void VelocitySmoother::velocityCB(const geometry_msgs::Twist::ConstPtr& msg)

v_inc = target_vel.linear.x – last_cmd_vel.linear.x;
w_inc = target_vel.angular.z – last_cmd_vel.angular.z;

// Calculate and normalise vectors A (desired velocity increment) and B (maximum velocity increment),
// where v acts as coordinate x and w as coordinate y; the sign of the angle from A to B determines
// which velocity (v or w) must be overconstrained to keep the direction provided as command
double MA = sqrt( v_inc * v_inc + w_inc * w_inc);
double MB = sqrt(max_v_inc * max_v_inc + max_w_inc * max_w_inc);

  double Av = std::abs(v_inc) / MA;
  double Aw = std::abs(w_inc) / MA;
  double Bv = max_v_inc / MB;
  double Bw = max_w_inc / MB;
  double theta = atan2(Bw, Bv) - atan2(Aw, Av);

if (theta < 0)
{
// overconstrain linear velocity
max_v_inc = (max_w_incstd::abs(v_inc))/std::abs(w_inc);
}
else
{
// overconstrain angular velocity
max_w_inc = (max_v_inc
std::abs(w_inc))/std::abs(v_inc);
}

  if (std::abs(v_inc) > max_v_inc)
  {
    // we must limit linear velocity
    cmd_vel->linear.x  = last_cmd_vel.linear.x  + sign(v_inc)*max_v_inc;
  }

  if (std::abs(w_inc) > max_w_inc)
  {
    // we must limit angular velocity
    cmd_vel->angular.z = last_cmd_vel.angular.z + sign(w_inc)*max_w_inc;
  }

what is mean?

@corot
Copy link
Collaborator

corot commented Jul 5, 2017

If you constraint linear xor angular velocity, being both non zero, you will change the shape of your trajectory.
These lines constraint the other velocity (not need to respect the acceleration limits) to keep executing the same trajectory (but slower)

@lahyeon
Copy link
Author

lahyeon commented Jul 7, 2017

I appreciate your help!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants