Skip to content

Commit

Permalink
Exception handling for transfrom
Browse files Browse the repository at this point in the history
  • Loading branch information
ibrahiminfinite committed Aug 3, 2023
1 parent b1d7b4a commit ec6249a
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 7 deletions.
4 changes: 3 additions & 1 deletion moveit_ros/moveit_servo/include/moveit_servo/servo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,8 +134,10 @@ class Servo
private:
/**
* \brief Convert a give twist command to planning frame
* (This implementation assumes that source and target frames are stationary)
* See issue: https://github.com/ros-planning/moveit2/issues/2150
* @param command The twist command to be converted
* @return The transformed twist command
* @return The transformed twist command.
*/
const TwistCommand toPlanningFrame(const TwistCommand& command);

Expand Down
29 changes: 23 additions & 6 deletions moveit_ros/moveit_servo/src/servo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,16 +327,33 @@ Eigen::VectorXd Servo::jointDeltaFromCommand(const ServoInput& command, moveit::
}
else if (expected_type == CommandType::TWIST)
{
const TwistCommand command_in_planning_frame = toPlanningFrame(std::get<TwistCommand>(command));
delta_result = jointDeltaFromTwist(command_in_planning_frame, robot_state, servo_params_);
servo_status_ = delta_result.first;
try
{
const TwistCommand command_in_planning_frame = toPlanningFrame(std::get<TwistCommand>(command));
delta_result = jointDeltaFromTwist(command_in_planning_frame, robot_state, servo_params_);
servo_status_ = delta_result.first;
}
catch (tf2::TransformException& ex)
{
servo_status_ = StatusCode::INVALID;
RCLCPP_ERROR_STREAM(LOGGER, "Could not transform twist to planning frame.");
}
}
else if (expected_type == CommandType::POSE)
{
const PoseCommand command_in_planning_frame = toPlanningFrame(std::get<PoseCommand>(command));
delta_result = jointDeltaFromPose(command_in_planning_frame, robot_state, servo_params_);
servo_status_ = delta_result.first;
try
{
const PoseCommand command_in_planning_frame = toPlanningFrame(std::get<PoseCommand>(command));
delta_result = jointDeltaFromPose(command_in_planning_frame, robot_state, servo_params_);
servo_status_ = delta_result.first;
}
catch (tf2::TransformException& ex)
{
servo_status_ = StatusCode::INVALID;
RCLCPP_ERROR_STREAM(LOGGER, "Could not transform pose to planning frame.");
}
}

if (servo_status_ != StatusCode::INVALID)
{
joint_position_deltas = delta_result.second;
Expand Down

0 comments on commit ec6249a

Please sign in to comment.