Skip to content

Commit

Permalink
Move wraparound logic into separate function
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 14, 2023
1 parent fd49c22 commit b0d87d9
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,18 +44,31 @@ class Trajectory
const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);

/* Set the point before the trajectory message is replaced/appended
/**
* Set the point before the trajectory message is replaced/appended
* Example: if we receive a new trajectory message and it's first point is 0.5 seconds
* from the current one, we call this function to log the current state, then
* append/replace the current trajectory
* \param normalize_joint_error Vector of boolean where true value corresponds to a joint that
* \param joints_angle_wraparound Vector of boolean where true value corresponds to a joint that
* wrap around (ie. is continuous).
*/
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
void set_point_before_trajectory_msg(
const rclcpp::Time & current_time,
const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
const std::vector<bool> & normalize_joint_error = std::vector<bool>());
const std::vector<bool> & joints_angle_wraparound = std::vector<bool>());

/**
* \param current_position The current position given from the controller, which will be adapted.
* \param next_position Next position from which to compute the wraparound offset, i.e.,
* the first trajectory point
* \param joints_angle_wraparound Vector of boolean where true value corresponds to a joint that
* wrap around (ie. is continuous).
*/
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
void wraparound_joint(
std::vector<double> & current_position, const std::vector<double> next_position,
const std::vector<bool> & joints_angle_wraparound);

JOINT_TRAJECTORY_CONTROLLER_PUBLIC
void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
Expand Down
36 changes: 22 additions & 14 deletions joint_trajectory_controller/src/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,28 +46,36 @@ Trajectory::Trajectory(
void Trajectory::set_point_before_trajectory_msg(
const rclcpp::Time & current_time,
const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
const std::vector<bool> & normalize_joint_error)
const std::vector<bool> & joints_angle_wraparound)
{
time_before_traj_msg_ = current_time;
state_before_traj_msg_ = current_point;

if (!normalize_joint_error.empty())
// Compute offsets due to wrapping joints
wraparound_joint(
state_before_traj_msg_.positions, trajectory_msg_->points[0].positions,
joints_angle_wraparound);
}

void Trajectory::wraparound_joint(
std::vector<double> & current_position, const std::vector<double> next_position,
const std::vector<bool> & joints_angle_wraparound)
{
double dist;
// joints_angle_wraparound is even empty, or has the same size as the number of joints
for (size_t i = 0; i < joints_angle_wraparound.size(); i++)
{
for (size_t i = 0; i < current_point.positions.size(); i++)
if (joints_angle_wraparound[i])
{
if (normalize_joint_error[i])
dist = angles::shortest_angular_distance(current_position[i], next_position[i]);

// Deal with singularity at M_PI shortest distance
if (std::abs(std::abs(dist) - M_PI) < 1e-9)
{
double prev_position = state_before_traj_msg_.positions[i];
double next_position = trajectory_msg_->points[0].positions[i];
double dist = angles::shortest_angular_distance(prev_position, next_position);

// Deal with singularity at M_PI shortest distance
if (std::abs(std::abs(dist) - M_PI) < 1e-9)
{
dist = next_position > prev_position ? std::abs(dist) : -std::abs(dist);
}
state_before_traj_msg_.positions[i] = next_position - dist;
dist = next_position[i] > current_position[i] ? std::abs(dist) : -std::abs(dist);
}

current_position[i] = next_position[i] - dist;
}
}
}
Expand Down

0 comments on commit b0d87d9

Please sign in to comment.