2 #include <controller_manager_msgs/ListControllers.h>
3 #include <controller_manager_msgs/SwitchController.h>
4 #include <franka/duration.h>
10 #include <franka_msgs/SetEEFrame.h>
11 #include <franka_msgs/SetForceTorqueCollisionBehavior.h>
12 #include <franka_msgs/SetKFrame.h>
13 #include <franka_msgs/SetLoad.h>
16 #include <std_msgs/Bool.h>
17 #include <std_srvs/SetBool.h>
18 #include <Eigen/Dense>
19 #include <boost/algorithm/clamp.hpp>
20 #include <boost/optional.hpp>
28 using boost::sml::state;
34 gazebo::physics::ModelPtr parent,
36 std::vector<transmission_interface::TransmissionInfo> transmissions) {
37 model_nh.
param<std::string>(
"arm_id", this->
arm_id_, robot_namespace);
38 if (this->arm_id_ != robot_namespace) {
41 "Caution: Robot names differ! Read 'arm_id: "
42 << this->arm_id_ <<
"' from parameter server but URDF defines '<robotNamespace>"
43 << robot_namespace <<
"</robotNamespace>'. Will use '" << this->arm_id_ <<
"'!");
51 msg.data =
static_cast<decltype(msg.data)
>(
false);
54 this->
action_recovery_ = std::make_unique<SimpleActionServer<franka_msgs::ErrorRecoveryAction>>(
55 model_nh,
"franka_control/error_recovery",
56 [&](
const franka_msgs::ErrorRecoveryGoalConstPtr&
goal) {
57 if (this->
robot_state_.robot_mode == franka::RobotMode::kUserStopped) {
59 "Cannot recover errors since the user stop seems still pressed");
68 }
catch (
const std::runtime_error& e) {
76 #if GAZEBO_MAJOR_VERSION >= 8
77 gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics();
79 gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->GetPhysicsEngine();
86 auto gravity = physics->World()->Gravity();
93 for (
const auto& transmission : transmissions) {
94 if (transmission.type_ !=
"transmission_interface/SimpleTransmission") {
97 if (transmission.joints_.empty()) {
99 "Transmission " << transmission.name_ <<
" has no associated joints.");
102 if (transmission.joints_.size() > 1) {
106 << transmission.name_
107 <<
" has more than one joint. Currently the franka robot hardware simulation "
108 <<
" interface only supports one.");
113 auto joint = std::make_shared<franka_gazebo::Joint>();
114 joint->name = transmission.joints_[0].name_;
115 if (
urdf ==
nullptr) {
117 "franka_hw_sim",
"Could not find any URDF model. Was it loaded on the parameter server?");
120 auto urdf_joint =
urdf->getJoint(joint->name);
121 if (not urdf_joint) {
123 "Could not get joint '" << joint->name <<
"' from URDF");
126 joint->type = urdf_joint->type;
128 joint->axis = Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z);
131 gazebo::physics::JointPtr handle = parent->GetJoint(joint->name);
135 <<
"' which is not in the gazebo model.");
138 joint->handle = handle;
140 if (joint->name.find(
arm_id_ +
"_finger_joint") != std::string::npos) {
141 joint->control_method =
EFFORT;
143 this->
joints_.emplace(joint->name, joint);
149 for (
auto& pair : this->
joints_) {
154 for (
const auto& transmission : transmissions) {
155 for (
const auto& k_interface : transmission.joints_[0].hardware_interfaces_) {
156 auto joint = this->joints_[transmission.joints_[0].name_];
157 if (transmission.type_ ==
"transmission_interface/SimpleTransmission") {
159 << joint->name <<
"': " << k_interface);
160 if (k_interface ==
"hardware_interface/EffortJointInterface") {
164 if (k_interface ==
"hardware_interface/PositionJointInterface") {
166 joint->position_controller.initParam(robot_namespace +
167 "/motion_generators/position/gains/" + joint->name);
171 if (k_interface ==
"hardware_interface/VelocityJointInterface") {
173 joint->velocity_controller.initParam(robot_namespace +
174 "/motion_generators/velocity/gains/" + joint->name);
180 if (transmission.type_ ==
"franka_hw/FrankaStateInterface") {
182 "Found transmission interface '" << transmission.type_ <<
"'");
187 }
catch (
const std::invalid_argument& e) {
193 if (transmission.type_ ==
"franka_hw/FrankaModelInterface") {
195 "Found transmission interface '" << transmission.type_ <<
"'");
196 double singularity_threshold;
197 model_nh.param<
double>(
"singularity_warning_threshold", singularity_threshold, -1);
202 }
catch (
const std::invalid_argument& e) {
208 << joint->name <<
"': " << k_interface);
217 assert(this->
fsi_.getNames().size() == 1);
218 assert(this->
fmi_.getNames().size() == 1);
235 &joint->velocity, &joint->effort));
254 const std::string& robot,
257 if (transmission.
joints_.size() != 7) {
258 throw std::invalid_argument(
259 "Cannot create franka_hw/FrankaStateInterface for robot '" + robot +
"_robot' because " +
260 std::to_string(transmission.
joints_.size()) +
261 " joints were found beneath the <transmission> tag, but 7 are required.");
265 this->
robot_state_.robot_mode = franka::RobotMode::kIdle;
268 for (
const auto& joint : transmission.
joints_) {
269 if (not
urdf.getJoint(joint.name_)) {
270 throw std::invalid_argument(
"Cannot create franka_hw/FrankaStateInterface for robot '" +
271 robot +
"_robot' because the specified joint '" + joint.name_ +
272 "' in the <transmission> tag cannot be found in the URDF");
275 "Found joint " << joint.name_ <<
" to belong to a Panda robot");
281 const std::string& robot,
284 double singularity_threshold) {
285 if (transmission.
joints_.size() != 2) {
286 throw std::invalid_argument(
287 "Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
"_model' because " +
288 std::to_string(transmission.
joints_.size()) +
289 " joints were found beneath the <transmission> tag, but 2 are required.");
292 for (
const auto& joint : transmission.
joints_) {
293 if (not
urdf.getJoint(joint.name_)) {
294 if (not
urdf.getJoint(joint.name_)) {
295 throw std::invalid_argument(
"Cannot create franka_hw/FrankaModelInterface for robot '" +
296 robot +
"_model' because the specified joint '" + joint.name_ +
297 "' in the <transmission> tag cannot be found in the URDF");
302 std::find_if(transmission.
joints_.begin(), transmission.
joints_.end(),
304 if (root == transmission.
joints_.end()) {
305 throw std::invalid_argument(
"Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
306 "_model' because no <joint> with <role>root</root> can be found "
307 "in the <transmission>");
310 std::find_if(transmission.
joints_.begin(), transmission.
joints_.end(),
312 if (tip == transmission.
joints_.end()) {
313 throw std::invalid_argument(
"Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
314 "_model' because no <joint> with <role>tip</role> can be found "
315 "in the <transmission>");
318 auto root_link =
urdf.getJoint(root->name_)->parent_link_name;
319 auto tip_link =
urdf.getJoint(tip->name_)->child_link_name;
322 std::make_unique<franka_gazebo::ModelKDL>(
urdf, root_link, tip_link, singularity_threshold);
324 }
catch (
const std::invalid_argument& e) {
325 throw std::invalid_argument(
"Cannot create franka_hw/FrankaModelInterface for robot '" + robot +
326 "_model'. " + e.what());
328 this->
fmi_.registerHandle(
334 nh.
advertiseService<franka_msgs::SetEEFrame::Request, franka_msgs::SetEEFrame::Response>(
335 "franka_control/set_EE_frame", [&](
auto& request,
auto&
response) {
337 this->
arm_id_ <<
": Setting NE_T_EE transformation");
338 std::copy(request.NE_T_EE.cbegin(), request.NE_T_EE.cend(),
339 this->robot_state_.NE_T_EE.begin());
344 this->
service_set_k_ = franka_hw::advertiseService<franka_msgs::SetKFrame>(
345 nh,
"franka_control/set_K_frame", [&](
auto& request,
auto&
response) {
347 std::copy(request.EE_T_K.cbegin(), request.EE_T_K.cend(),
348 this->robot_state_.EE_T_K.begin());
354 nh,
"franka_control/set_load", [&](
auto& request,
auto&
response) {
357 std::copy(request.F_x_center_load.cbegin(), request.F_x_center_load.cend(),
358 this->robot_state_.F_x_Cload.begin());
359 std::copy(request.load_inertia.cbegin(), request.load_inertia.cend(),
360 this->robot_state_.I_load.begin());
366 franka_hw::advertiseService<franka_msgs::SetForceTorqueCollisionBehavior>(
367 nh,
"franka_control/set_force_torque_collision_behavior",
368 [&](
auto& request,
auto&
response) {
371 for (
int i = 0; i < 7; i++) {
372 std::string
name = this->
arm_id_ +
"_joint" + std::to_string(i + 1);
373 this->
joints_[name]->contact_threshold =
374 request.lower_torque_thresholds_nominal.at(i);
375 this->
joints_[name]->collision_threshold =
376 request.upper_torque_thresholds_nominal.at(i);
379 std::move(request.lower_force_thresholds_nominal.begin(),
380 request.lower_force_thresholds_nominal.end(),
381 this->lower_force_thresholds_nominal_.begin());
382 std::move(request.upper_force_thresholds_nominal.begin(),
383 request.upper_force_thresholds_nominal.end(),
384 this->upper_force_thresholds_nominal_.begin());
390 nh.
advertiseService<std_srvs::SetBool::Request, std_srvs::SetBool::Response>(
391 "franka_control/set_user_stop", [&](
auto& request,
auto&
response) {
392 this->
sm_.process_event(
UserStop{
static_cast<bool>(request.data)});
397 "controller_manager/list_controllers");
399 "controller_manager/switch_controller");
406 throw std::runtime_error(
"Cannot find service '" +
name +
407 "'. Is the controller_manager running?");
410 controller_manager_msgs::ListControllers list;
412 throw std::runtime_error(
"Service call '" +
name +
"' failed");
415 controller_manager_msgs::SwitchController swtch;
416 for (
const auto& controller : list.response.controller) {
417 if (controller.state !=
"running") {
420 swtch.request.stop_controllers.push_back(controller.name);
421 swtch.request.start_controllers.push_back(controller.name);
423 swtch.request.start_asap =
static_cast<decltype(swtch.request.start_asap)
>(
true);
424 swtch.request.strictness = controller_manager_msgs::SwitchControllerRequest::STRICT;
426 not
static_cast<bool>(swtch.response.ok)) {
433 for (
const auto& pair : this->
joints_) {
434 auto joint = pair.second;
435 joint->update(period);
444 switch (joint.
type) {
445 case urdf::Joint::REVOLUTE:
447 kJointUpperLimit,
error);
449 case urdf::Joint::PRISMATIC:
451 boost::algorithm::clamp(setpoint - joint.
position, kJointLowerLimit, kJointUpperLimit);
454 std::string error_message =
455 "Only revolute or prismatic joints are allowed for position control right now";
457 throw std::invalid_argument(error_message);
465 return boost::algorithm::clamp(
473 for (
auto& pair : this->
joints_) {
474 auto joint = pair.second;
480 if (not
sm_.is(state<Move>) and not
contains(pair.first,
"finger_joint")) {
482 }
else if (joint->control_method ==
POSITION) {
484 }
else if (joint->control_method ==
VELOCITY) {
486 }
else if (joint->control_method ==
EFFORT) {
488 effort = joint->command;
492 std::string prefix = this->
arm_id_ +
"_joint";
493 if (pair.first.rfind(prefix, 0) != std::string::npos) {
494 int i = std::stoi(pair.first.substr(prefix.size())) - 1;
495 joint->gravity = g.at(i);
497 effort += joint->gravity;
500 if (not std::isfinite(effort)) {
502 "Command for " << joint->name <<
"is not finite, won't send to robot");
505 joint->handle->SetForce(0, effort);
518 nh.
param<std::string>(
"I_load", I_load,
"0 0 0 0 0 0 0 0 0");
519 this->
robot_state_.I_load = readArray<9>(I_load,
"I_load");
521 std::string F_x_Cload;
522 nh.
param<std::string>(
"F_x_Cload", F_x_Cload,
"0 0 0");
523 this->
robot_state_.F_x_Cload = readArray<3>(F_x_Cload,
"F_x_Cload");
526 nh.
param<std::string>(
"NE_T_EE", NE_T_EE,
"1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1");
527 this->
robot_state_.NE_T_EE = readArray<16>(NE_T_EE,
"NE_T_EE");
530 nh.
param<std::string>(
"EE_T_K", EE_T_K,
"1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1");
531 this->
robot_state_.EE_T_K = readArray<16>(EE_T_K,
"EE_T_K");
533 std::string gravity_vector;
534 if (nh.
getParam(
"gravity_vector", gravity_vector)) {
535 this->
gravity_earth_ = readArray<3>(gravity_vector,
"gravity_vector");
540 "lower_torque_thresholds_nominal", nh, {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
543 "upper_torque_thresholds_nominal", nh, {20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0});
546 "lower_force_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
548 "upper_force_thresholds_nominal", nh, {20.0, 20.0, 20.0, 25.0, 25.0, 25.0});
550 for (
int i = 0; i < 7; i++) {
551 std::string
name = this->
arm_id_ +
"_joint" + std::to_string(i + 1);
552 this->
joints_[name]->contact_threshold = lower_torque_thresholds.at(i);
553 this->
joints_[name]->collision_threshold = upper_torque_thresholds.at(i);
556 }
catch (
const std::invalid_argument& e) {
565 auto hand_link = this->
arm_id_ +
"_hand";
566 auto hand =
urdf.getLink(hand_link);
567 if (hand !=
nullptr) {
569 "Found link '" << hand_link
570 <<
"' in URDF. Assuming it is defining the kinematics & "
571 "inertias of a Franka Hand Gripper.");
576 std::string def_i_ee =
"0.0 0 0 0 0.0 0 0 0 0.0";
577 std::string def_f_x_cee =
"0 0 0";
578 std::string def_f_t_ne =
"1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1";
579 if (not nh.
hasParam(
"F_T_NE") and hand !=
nullptr) {
582 def_f_t_ne =
"0.7071 -0.7071 0 0 0.7071 0.7071 0 0 0 0 1 0 0 0 0.1034 1";
585 nh.
param<std::string>(
"F_T_NE", F_T_NE, def_f_t_ne);
586 this->
robot_state_.F_T_NE = readArray<16>(F_T_NE,
"F_T_NE");
588 if (not nh.
hasParam(
"m_ee") and hand !=
nullptr) {
589 if (hand->inertial ==
nullptr) {
590 throw std::invalid_argument(
"Trying to use inertia of " + hand_link +
591 " but this link has no <inertial> tag defined in it.");
593 def_m_ee = hand->inertial->mass;
597 if (not nh.
hasParam(
"I_ee") and hand !=
nullptr) {
598 if (hand->inertial ==
nullptr) {
599 throw std::invalid_argument(
"Trying to use inertia of " + hand_link +
600 " but this link has no <inertial> tag defined in it.");
603 def_i_ee = std::to_string(hand->inertial->ixx) +
" " + std::to_string(hand->inertial->ixy) +
" " + std::to_string(hand->inertial->ixz) +
" "
604 + std::to_string(hand->inertial->ixy) +
" " + std::to_string(hand->inertial->iyy) +
" " + std::to_string(hand->inertial->iyz) +
" "
605 + std::to_string(hand->inertial->ixz) +
" " + std::to_string(hand->inertial->iyz) +
" " + std::to_string(hand->inertial->izz);
609 nh.
param<std::string>(
"I_ee", I_ee, def_i_ee);
612 if (not nh.
hasParam(
"F_x_Cee") and hand !=
nullptr) {
613 if (hand->inertial ==
nullptr) {
614 throw std::invalid_argument(
"Trying to use inertia of " + hand_link +
615 " but this link has no <inertial> tag defined in it.");
617 def_f_x_cee = std::to_string(hand->inertial->origin.position.x) +
" " +
618 std::to_string(hand->inertial->origin.position.y) +
" " +
619 std::to_string(hand->inertial->origin.position.z);
622 nh.
param<std::string>(
"F_x_Cee", F_x_Cee, def_f_x_cee);
623 this->
robot_state_.F_x_Cee = readArray<3>(F_x_Cee,
"F_x_Cee");
629 Eigen::Map<Eigen::Matrix4d>(this->
robot_state_.F_T_EE.data()) =
633 Eigen::Map<Eigen::Matrix3d>(this->
robot_state_.I_total.data()) =
635 Eigen::Vector3d(this->robot_state_.F_x_Cload.data()));
640 assert(this->
joints_.size() >= 7);
643 for (
int i = 0; i < 7; i++) {
644 std::string
name = this->
arm_id_ +
"_joint" + std::to_string(i + 1);
645 const auto& joint = this->
joints_.at(name);
651 this->
robot_state_.q_d[i] = joint->getDesiredPosition(mode);
652 this->
robot_state_.dq_d[i] = joint->getDesiredVelocity(mode);
653 this->
robot_state_.ddq_d[i] = joint->getDesiredAcceleration(mode);
654 this->
robot_state_.tau_J_d[i] = joint->getDesiredTorque(mode);
662 joint->desired_position = joint->position;
663 joint->stop_position = joint->position;
666 if (this->robot_initialized_) {
667 double tau_ext = joint->effort - joint->command + joint->gravity;
675 this->
robot_state_.joint_contact[i] =
static_cast<double>(joint->isInContact());
676 this->
robot_state_.joint_collision[i] =
static_cast<double>(joint->isInCollision());
680 Eigen::Map<Eigen::Matrix<double, 7, 1>> tau_ext(this->
robot_state_.tau_ext_hat_filtered.data());
681 Eigen::MatrixXd j0_transpose_pinv;
682 Eigen::MatrixXd jk_transpose_pinv;
683 Eigen::Matrix<double, 6, 7> j0(
684 this->
model_->zeroJacobian(franka::Frame::kStiffness, this->robot_state_).data());
685 Eigen::Matrix<double, 6, 7> jk(
686 this->
model_->bodyJacobian(franka::Frame::kStiffness, this->robot_state_).data());
690 Eigen::VectorXd f_ext_0 = j0_transpose_pinv * tau_ext;
691 Eigen::VectorXd f_ext_k = jk_transpose_pinv * tau_ext;
692 Eigen::VectorXd::Map(&this->
robot_state_.O_F_ext_hat_K[0], 6) = f_ext_0;
693 Eigen::VectorXd::Map(&this->
robot_state_.K_F_ext_hat_K[0], 6) = f_ext_k;
695 for (
int i = 0; i < this->
robot_state_.cartesian_contact.size(); i++) {
697 double fi = std::abs(f_ext_k(i));
707 #ifdef ENABLE_BASE_ACCELERATION
713 msg.data =
static_cast<decltype(msg.data)
>(
true);
719 const std::list<hardware_interface::ControllerInfo>& start_list,
720 const std::list<hardware_interface::ControllerInfo>& ) {
721 return std::all_of(start_list.cbegin(), start_list.cend(), [
this](
const auto& controller) {
722 return verifier_->isValidController(controller);
727 const std::list<hardware_interface::ControllerInfo>& stop_list) {
745 const std::list<hardware_interface::ControllerInfo>& controllers,
747 for (
const auto& controller : controllers) {
748 if (not
verifier_->isClaimingArmController(controller)) {
751 for (
const auto& resource : controller.claimed_resources) {
753 if (not control_method) {
756 for (
const auto& joint_name : resource.resources) {
757 auto& joint =
joints_.at(joint_name);
758 f(*joint, control_method.value());