Skip to content

Commit

Permalink
Declare wraparound_joint outside of trajectory class
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 19, 2023
1 parent f90c2af commit f6231f2
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -58,18 +58,6 @@ class Trajectory
const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
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 Expand Up @@ -206,6 +194,17 @@ inline std::vector<size_t> mapping(const T & t1, const T & t2)
return mapping_vector;
}

/**
* \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).
*/
void wraparound_joint(
std::vector<double> & current_position, const std::vector<double> next_position,
const std::vector<bool> & joints_angle_wraparound);

} // namespace joint_trajectory_controller

#endif // JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_
2 changes: 1 addition & 1 deletion joint_trajectory_controller/src/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ void Trajectory::set_point_before_trajectory_msg(
joints_angle_wraparound);
}

void Trajectory::wraparound_joint(
void wraparound_joint(
std::vector<double> & current_position, const std::vector<double> next_position,
const std::vector<bool> & joints_angle_wraparound)
{
Expand Down

0 comments on commit f6231f2

Please sign in to comment.