Skip to content

Commit

Permalink
Update comments
Browse files Browse the repository at this point in the history
Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>
  • Loading branch information
ibrahiminfinite and sea-bass committed Aug 16, 2023
1 parent 269e6ee commit f72311d
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 2 deletions.
4 changes: 3 additions & 1 deletion moveit_ros/moveit_servo/config/panda_simulated_config.yaml
Expand Up @@ -42,7 +42,9 @@ planning_frame: panda_link0 # The MoveIt planning frame. Often 'base_link' or '
## Other frames
ee_frame: panda_hand # The name of the end effector link, used to return the EE pose

command_frame_is_stationary: true # Twist commands are as seen from a stationary frame.
# If true, twist commands are given in a stationary frame; otherwise, they are in a moving frame.
# See https://github.com/ros-planning/moveit2/issues/2150 for more details
command_frame_is_stationary: true

## Configure handling of singularities and joint limits
lower_singularity_threshold: 17.0 # Start decelerating when the condition number hits this (close to singularity)
Expand Down
4 changes: 3 additions & 1 deletion moveit_ros/moveit_servo/config/test_config_panda.yaml
Expand Up @@ -42,7 +42,9 @@ planning_frame: panda_link0 # The MoveIt planning frame. Often 'base_link' or '

## Other frames
ee_frame: panda_hand # The name of the end effector link, used to return the EE pose
command_frame_is_stationary: true # Twist commands are as seem from the stationary frame.
# If true, twist commands are given in a stationary frame; otherwise, they are in a moving frame.
# See https://github.com/ros-planning/moveit2/issues/2150 for more details
command_frame_is_stationary: true

## Configure handling of singularities and joint limits
lower_singularity_threshold: 17.0 # Start decelerating when the condition number hits this (close to singularity)
Expand Down
2 changes: 2 additions & 0 deletions moveit_ros/moveit_servo/src/servo.cpp
Expand Up @@ -490,6 +490,8 @@ const TwistCommand Servo::toPlanningFrame(const TwistCommand& command)
tf2::doTransform(reordered_twist, reordered_twist, body_to_space_tf);
}

// else: the command is in the planning frame so no transformation is needed

// Reverse again to make it (linear, angular)
Eigen::VectorXd transformed_twist(6);
transformed_twist.head<3>() = reordered_twist.tail<3>();
Expand Down

0 comments on commit f72311d

Please sign in to comment.