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

Admittance robot description param #22

Open
wants to merge 37 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
37 commits
Select commit Hold shift + click to select a range
8348bc9
Use the urdf_ to set the robot_description in admittance controller
SyllogismRXS Apr 5, 2024
3021b08
Pass robot_description to kinematics_interface using input arg
SyllogismRXS Apr 9, 2024
9f87347
admittance_controller: skip large dt periods
SyllogismRXS Apr 15, 2024
e1b47c1
get robot_description correctly
Nibanovic Aug 1, 2024
95dbc20
correct for kinematics_interface initialize() API change
Nibanovic Aug 1, 2024
8fb7edf
enable pose-only goal in AdmittanceRule
Nibanovic Jul 31, 2024
b55cd2b
add a goal pose subscriber in admittance controller
Nibanovic Aug 1, 2024
fce1e28
move from Pose to PoseStamped
Nibanovic Aug 1, 2024
165de4c
overload admittance->update() to account for both joint_state and pos…
Nibanovic Aug 2, 2024
fa301f4
Fix wrong method name in write new controller doc (#1240)
mateusmenezes95 Aug 5, 2024
0401dd4
Update changelogs
bmagyar Aug 14, 2024
298df4b
4.12.1
bmagyar Aug 14, 2024
4a6456f
[Joint State Broadcaster] Publish the joint_states of joints present …
saikishor Aug 15, 2024
4ab22a5
Fixes tests to work with use_global_arguments NodeOptions parameter …
saikishor Aug 22, 2024
31f7fbe
Fix segfault at reconfigure of AdmittanceController (#1248)
firesurfer Aug 22, 2024
cdfc0af
Also test if python files were changed (#1264)
christophfroehlich Aug 22, 2024
f57eedd
Update changelogs
bmagyar Aug 22, 2024
20f6f0b
4.13.0
bmagyar Aug 22, 2024
1c4d58e
[JSB] Move the initialize of urdf::Model from on_activate to on_confi…
TakashiSato Aug 24, 2024
ce12694
rename get/set_state to get/set_lifecylce_state (#1250)
mamueluth Aug 26, 2024
3be3fe9
Fix bug for displaying all controllers (#1259)
fmrico Aug 26, 2024
a7b2af5
[PID Controller] Export state interfaces for easier chaining with oth…
saikishor Aug 29, 2024
c08bdab
Bump version of pre-commit hooks (#1279)
github-actions[bot] Sep 1, 2024
48a7f8b
Fix deprecation warning in paramater declaration (#1280)
kumar-sanjeeev Sep 11, 2024
1dc3d2a
fix(steering-odometry): handle infinite turning radius properly (#1285)
reinzor Sep 11, 2024
75ae6c9
Update changelogs
bmagyar Sep 11, 2024
57c50e5
4.14.0
bmagyar Sep 11, 2024
a2ec061
Use the urdf_ to set the robot_description in admittance controller
SyllogismRXS Apr 5, 2024
2757d44
Pass robot_description to kinematics_interface using input arg
SyllogismRXS Apr 9, 2024
8a58707
admittance_controller: skip large dt periods
SyllogismRXS Apr 15, 2024
8f5ae5f
get robot_description correctly
Nibanovic Aug 1, 2024
2631ae0
correct for kinematics_interface initialize() API change
Nibanovic Aug 1, 2024
99236f4
enable pose-only goal in AdmittanceRule
Nibanovic Jul 31, 2024
85f3bcf
add a goal pose subscriber in admittance controller
Nibanovic Aug 1, 2024
f8e580c
move from Pose to PoseStamped
Nibanovic Aug 1, 2024
0d88c35
overload admittance->update() to account for both joint_state and pos…
Nibanovic Aug 2, 2024
ad672aa
Merge branch 'admittance-robot-description-param' of github.com:Stogl…
YaraShahin Sep 23, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -111,16 +111,32 @@ class AdmittanceRule
controller_interface::return_type reset(const size_t num_joints);

/**
* Calculate all transforms needed for admittance control using the loader kinematics plugin. If
* Calculate transforms needed for admittance control using the loader kinematics plugin. If
* the transform does not exist in the kinematics model, then TF will be used for lookup. The
* return value is true if all transformation are calculated without an error
* \param[in] current_joint_state current joint state of the robot
* \param[out] success true if no calls to the kinematics interface fail
*/
bool get_current_state_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state);
/**
* Calculate ft_sensor_link -> base_link transform needed for admittance control using the loader kinematics plugin. If
* the transform does not exist in the kinematics model, then TF will be used for lookup. The
* return value is true if all transformation are calculated without an error
* \param[in] reference_pose input ft sensor reference pose
* \param[out] success true if no calls to the kinematics interface fail
*/
bool get_all_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
bool get_reference_state_transforms(
const geometry_msgs::msg::PoseStamped & reference_pose);
/**
* Calculate ft_sensor_link -> base_link transform needed for admittance control using the loader kinematics plugin. If
* the transform does not exist in the kinematics model, then TF will be used for lookup. The
* return value is true if all transformation are calculated without an error
* \param[in] reference_joint_state input reference joint state
* \param[out] success true if no calls to the kinematics interface fail
*/
bool get_reference_state_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state);

/**
* Updates parameter_ struct if any parameters have changed since last update. Parameter dependent
Expand All @@ -130,12 +146,12 @@ class AdmittanceRule
void apply_parameters_update();

/**
* Calculate 'desired joint states' based on the 'measured force', 'reference joint state', and
* Calculate 'desired joint states' based on the 'measured force', 'reference goal pose', and
* 'current_joint_state'.
*
* \param[in] current_joint_state current joint state of the robot
* \param[in] measured_wrench most recent measured wrench from force torque sensor
* \param[in] reference_pose input joint state reference
* \param[in] reference_pose input reference pose
* \param[in] period time in seconds since last controller update
* \param[out] desired_joint_state joint state reference after the admittance offset is applied to
* the input reference
Expand All @@ -144,6 +160,23 @@ class AdmittanceRule
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::Wrench & measured_wrench,
const geometry_msgs::msg::PoseStamped & reference_pose,
const rclcpp::Duration & period,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);

/**
* Calculate 'desired joint states' based on the 'measured force', 'reference joint state', and
* 'current_joint_state'.
*
* \param[in] current_joint_state current joint state of the robot
* \param[in] measured_wrench most recent measured wrench from force torque sensor
* \param[in] reference_joint_state input joint state reference
* \param[in] period time in seconds since last controller update
* \param[out] desired_joint_state joint state reference after the admittance offset is applied to
* the input reference
*/
controller_interface::return_type update(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::Wrench & measured_wrench,
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
const rclcpp::Duration & period,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
Expand All @@ -170,6 +203,15 @@ class AdmittanceRule
admittance_controller::Params parameters_;

protected:
/**
* Populate the AdmittanceState member using the current AdmittanceTransforms
* \param[in] current_joint_state
* \param[in] measured_wrench
*/
void get_admittance_state_from_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::Wrench & measured_wrench);

/**
* Calculates the admittance rule from given the robot's current joint angles. The admittance
* controller state input is updated with the new calculated values. A boolean value is returned
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,16 +148,11 @@ void AdmittanceRule::apply_parameters_update()
}


bool AdmittanceRule::get_all_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::PoseStamped & reference_pose)
bool AdmittanceRule::get_current_state_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state)
{
// get reference transforms
bool success=true;
tf2::fromMsg(reference_pose.pose, admittance_transforms_.ref_base_ft_);

// get transforms at current configuration
success &= kinematics_->calculate_link_transform(
bool success = kinematics_->calculate_link_transform(
current_joint_state.positions, parameters_.ft_sensor.frame.id, admittance_transforms_.base_ft_);
success &= kinematics_->calculate_link_transform(
current_joint_state.positions, parameters_.kinematics.tip, admittance_transforms_.base_tip_);
Expand All @@ -173,13 +168,26 @@ bool AdmittanceRule::get_all_transforms(

return success;
}
bool AdmittanceRule::get_reference_state_transforms(
const geometry_msgs::msg::PoseStamped & reference_pose)
{
tf2::fromMsg(reference_pose.pose, admittance_transforms_.ref_base_ft_);
return true;
}
bool AdmittanceRule::get_reference_state_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state)
{
bool success = kinematics_->calculate_link_transform(
reference_joint_state.positions, parameters_.ft_sensor.frame.id,
admittance_transforms_.ref_base_ft_);
return success;
}

// Update from reference joint states
controller_interface::return_type AdmittanceRule::update(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::Wrench & measured_wrench,
const geometry_msgs::msg::PoseStamped & reference_pose,
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
{
const double dt = period.seconds();
Expand All @@ -188,25 +196,9 @@ controller_interface::return_type AdmittanceRule::update(
{
apply_parameters_update();
}
bool success = get_all_transforms(current_joint_state, reference_pose);
// apply filter and update wrench_world_ vector
Eigen::Matrix<double, 3, 3> rot_world_sensor =
admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_ft_.rotation();
Eigen::Matrix<double, 3, 3> rot_world_cog =
admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_cog_.rotation();
process_wrench_measurements(measured_wrench, rot_world_sensor, rot_world_cog);

// transform wrench_world_ into base frame
admittance_state_.wrench_base.block<3, 1>(0, 0) =
admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(0, 0);
admittance_state_.wrench_base.block<3, 1>(3, 0) =
admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(3, 0);

// Compute admittance control law
vec_to_eigen(current_joint_state.positions, admittance_state_.current_joint_pos);
admittance_state_.rot_base_control = admittance_transforms_.base_control_.rotation();
admittance_state_.ref_trans_base_ft = admittance_transforms_.ref_base_ft_;
admittance_state_.ft_sensor_frame = parameters_.ft_sensor.frame.id;
bool success = get_current_state_transforms(current_joint_state);
success &= get_reference_state_transforms(reference_joint_state);
get_admittance_state_from_transforms(current_joint_state, measured_wrench);
success &= calculate_admittance_rule(admittance_state_, dt);

// if a failure occurred during any kinematics interface calls, return an error and don't
Expand All @@ -227,10 +219,69 @@ controller_interface::return_type AdmittanceRule::update(
desired_joint_state.accelerations[i] =
reference_joint_state.accelerations[i] + admittance_state_.joint_acc[i];
}
return controller_interface::return_type::OK;
}

controller_interface::return_type AdmittanceRule::update(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::Wrench & measured_wrench,
const geometry_msgs::msg::PoseStamped & reference_pose,
const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
{
const double dt = period.seconds();

if (parameters_.enable_parameter_update_without_reactivation)
{
apply_parameters_update();
}
bool success = get_current_state_transforms(current_joint_state);
success &= get_reference_state_transforms(reference_pose);
get_admittance_state_from_transforms(current_joint_state, measured_wrench);
success &= calculate_admittance_rule(admittance_state_, dt);

// if a failure occurred during any kinematics interface calls, return an error and
// remain at current state
if (!success)
{
desired_joint_state = current_joint_state;
return controller_interface::return_type::ERROR;
}

// update joint desired joint state
for (size_t i = 0; i < num_joints_; ++i)
{
desired_joint_state.positions[i] = admittance_state_.joint_pos[i];
desired_joint_state.velocities[i] = admittance_state_.joint_vel[i];
desired_joint_state.accelerations[i] = admittance_state_.joint_acc[i];
}

return controller_interface::return_type::OK;
}

void AdmittanceRule::get_admittance_state_from_transforms(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
const geometry_msgs::msg::Wrench & measured_wrench)
{
// apply filter and update wrench_world_ vector
Eigen::Matrix<double, 3, 3> rot_world_sensor =
admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_ft_.rotation();
Eigen::Matrix<double, 3, 3> rot_world_cog =
admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_cog_.rotation();
process_wrench_measurements(measured_wrench, rot_world_sensor, rot_world_cog);

// transform wrench_world_ into base frame
admittance_state_.wrench_base.block<3, 1>(0, 0) =
admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(0, 0);
admittance_state_.wrench_base.block<3, 1>(3, 0) =
admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(3, 0);

// Compute admittance control law
vec_to_eigen(current_joint_state.positions, admittance_state_.current_joint_pos);
admittance_state_.rot_base_control = admittance_transforms_.base_control_.rotation();
admittance_state_.ref_trans_base_ft = admittance_transforms_.ref_base_ft_;
admittance_state_.ft_sensor_frame = parameters_.ft_sensor.frame.id;
}

bool AdmittanceRule::calculate_admittance_rule(AdmittanceState & admittance_state, double dt)
{
// Create stiffness matrix in base frame. The user-provided values of admittance_state.stiffness
Expand Down
13 changes: 12 additions & 1 deletion admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -427,7 +427,18 @@ controller_interface::return_type AdmittanceController::update_and_write_command
read_state_from_hardware(joint_state_, ft_values_);

// apply admittance control to reference to determine desired state
admittance_->update(joint_state_, ft_values_, *goal_pose_msg_, reference_, period, reference_admittance_);

/* some flag that determines whether we call the update() with goal_pose or with joint reference.
How can we know here whether the reference was updated from subscribers or from itnerfaces?

if(updated_from_subscribers)
admittance_->update(joint_state_, ft_values_, *goal_pose_msg_, period, reference_admittance_);
else
admittance_->update(joint_state_, ft_values_, reference_, period, reference_admittance_);

*/

admittance_->update(joint_state_, ft_values_, *goal_pose_msg_, period, reference_admittance_);
Comment on lines +431 to +441

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@Nibanovic via parmeter maybe?


// write calculated values to joint interfaces
write_state_to_hardware(reference_admittance_);
Expand Down
Loading