franka_state_controller.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
4 
5 #include <cmath>
6 #include <memory>
7 #include <mutex>
8 #include <string>
9 
10 #include <franka/errors.h>
12 #include <franka_msgs/Errors.h>
15 #include <ros/ros.h>
16 #include <tf/tf.h>
17 #include <tf/transform_datatypes.h>
18 
19 namespace {
20 
21 tf::Transform convertArrayToTf(const std::array<double, 16>& transform) {
22  tf::Matrix3x3 rotation(transform[0], transform[4], transform[8], transform[1], transform[5],
23  transform[9], transform[2], transform[6], transform[10]);
24  tf::Vector3 translation(transform[12], transform[13], transform[14]);
25  return tf::Transform(rotation, translation);
26 }
27 
28 franka_msgs::Errors errorsToMessage(const franka::Errors& error) {
29  franka_msgs::Errors message;
30  message.joint_position_limits_violation =
31  static_cast<decltype(message.joint_position_limits_violation)>(
33  message.cartesian_position_limits_violation =
34  static_cast<decltype(message.cartesian_position_limits_violation)>(
36  message.self_collision_avoidance_violation =
37  static_cast<decltype(message.self_collision_avoidance_violation)>(
39  message.joint_velocity_violation =
40  static_cast<decltype(message.joint_velocity_violation)>(error.joint_velocity_violation);
41  message.cartesian_velocity_violation =
42  static_cast<decltype(message.cartesian_velocity_violation)>(
44  message.force_control_safety_violation =
45  static_cast<decltype(message.force_control_safety_violation)>(
47  message.joint_reflex = static_cast<decltype(message.joint_reflex)>(error.joint_reflex);
48  message.cartesian_reflex =
49  static_cast<decltype(message.cartesian_reflex)>(error.cartesian_reflex);
50  message.max_goal_pose_deviation_violation =
51  static_cast<decltype(message.max_goal_pose_deviation_violation)>(
53  message.max_path_pose_deviation_violation =
54  static_cast<decltype(message.max_path_pose_deviation_violation)>(
56  message.cartesian_velocity_profile_safety_violation =
57  static_cast<decltype(message.cartesian_velocity_profile_safety_violation)>(
59  message.joint_position_motion_generator_start_pose_invalid =
60  static_cast<decltype(message.joint_position_motion_generator_start_pose_invalid)>(
62  message.joint_motion_generator_position_limits_violation =
63  static_cast<decltype(message.joint_motion_generator_position_limits_violation)>(
65  message.joint_motion_generator_velocity_limits_violation =
66  static_cast<decltype(message.joint_motion_generator_velocity_limits_violation)>(
68  message.joint_motion_generator_velocity_discontinuity =
69  static_cast<decltype(message.joint_motion_generator_velocity_discontinuity)>(
71  message.joint_motion_generator_acceleration_discontinuity =
72  static_cast<decltype(message.joint_motion_generator_acceleration_discontinuity)>(
74  message.cartesian_position_motion_generator_start_pose_invalid =
75  static_cast<decltype(message.cartesian_position_motion_generator_start_pose_invalid)>(
77  message.cartesian_motion_generator_elbow_limit_violation =
78  static_cast<decltype(message.cartesian_motion_generator_elbow_limit_violation)>(
80  message.cartesian_motion_generator_velocity_limits_violation =
81  static_cast<decltype(message.cartesian_motion_generator_velocity_limits_violation)>(
83  message.cartesian_motion_generator_velocity_discontinuity =
84  static_cast<decltype(message.cartesian_motion_generator_velocity_discontinuity)>(
86  message.cartesian_motion_generator_acceleration_discontinuity =
87  static_cast<decltype(message.cartesian_motion_generator_acceleration_discontinuity)>(
89  message.cartesian_motion_generator_elbow_sign_inconsistent =
90  static_cast<decltype(message.cartesian_motion_generator_elbow_sign_inconsistent)>(
92  message.cartesian_motion_generator_start_elbow_invalid =
93  static_cast<decltype(message.cartesian_motion_generator_start_elbow_invalid)>(
95  message.cartesian_motion_generator_joint_position_limits_violation =
96  static_cast<decltype(message.cartesian_motion_generator_joint_position_limits_violation)>(
98  message.cartesian_motion_generator_joint_velocity_limits_violation =
99  static_cast<decltype(message.cartesian_motion_generator_joint_velocity_limits_violation)>(
101  message.cartesian_motion_generator_joint_velocity_discontinuity =
102  static_cast<decltype(message.cartesian_motion_generator_joint_velocity_discontinuity)>(
104  message.cartesian_motion_generator_joint_acceleration_discontinuity =
105  static_cast<decltype(message.cartesian_motion_generator_joint_acceleration_discontinuity)>(
107  message.cartesian_position_motion_generator_invalid_frame =
108  static_cast<decltype(message.cartesian_position_motion_generator_invalid_frame)>(
110  message.force_controller_desired_force_tolerance_violation =
111  static_cast<decltype(message.force_controller_desired_force_tolerance_violation)>(
113  message.controller_torque_discontinuity =
114  static_cast<decltype(message.controller_torque_discontinuity)>(
116  message.start_elbow_sign_inconsistent =
117  static_cast<decltype(message.start_elbow_sign_inconsistent)>(
119  message.communication_constraints_violation =
120  static_cast<decltype(message.communication_constraints_violation)>(
122  message.power_limit_violation =
123  static_cast<decltype(message.power_limit_violation)>(error.power_limit_violation);
124  message.joint_p2p_insufficient_torque_for_planning =
125  static_cast<decltype(message.joint_p2p_insufficient_torque_for_planning)>(
127  message.tau_j_range_violation =
128  static_cast<decltype(message.tau_j_range_violation)>(error.tau_j_range_violation);
129  message.instability_detected =
130  static_cast<decltype(message.instability_detected)>(error.instability_detected);
131  message.joint_move_in_wrong_direction =
132  static_cast<decltype(message.joint_move_in_wrong_direction)>(
134 #ifdef ENABLE_BASE_ACCELERATION
135  message.cartesian_spline_motion_generator_violation =
136  static_cast<decltype(message.cartesian_spline_motion_generator_violation)>(
137  error.cartesian_spline_motion_generator_violation);
138  message.joint_via_motion_generator_planning_joint_limit_violation =
139  static_cast<decltype(message.joint_via_motion_generator_planning_joint_limit_violation)>(
140  error.joint_via_motion_generator_planning_joint_limit_violation);
141  message.base_acceleration_initialization_timeout =
142  static_cast<decltype(message.base_acceleration_initialization_timeout)>(
143  error.base_acceleration_initialization_timeout);
144  message.base_acceleration_invalid_reading =
145  static_cast<decltype(message.base_acceleration_invalid_reading)>(
146  error.base_acceleration_invalid_reading);
147 #endif
148  return message;
149 }
150 
151 } // anonymous namespace
152 
153 namespace franka_control {
154 
156  ros::NodeHandle& root_node_handle,
157  ros::NodeHandle& controller_node_handle) {
159  if (franka_state_interface_ == nullptr) {
160  ROS_ERROR("FrankaStateController: Could not get Franka state interface from hardware");
161  return false;
162  }
163  if (!controller_node_handle.getParam("arm_id", arm_id_)) {
164  ROS_ERROR("FrankaStateController: Could not get parameter arm_id");
165  return false;
166  }
167  double publish_rate(30.0);
168  if (!controller_node_handle.getParam("publish_rate", publish_rate)) {
169  ROS_INFO_STREAM("FrankaStateController: Did not find publish_rate. Using default "
170  << publish_rate << " [Hz].");
171  }
173 
174  if (!controller_node_handle.getParam("joint_names", joint_names_) ||
175  joint_names_.size() != robot_state_.q.size()) {
176  ROS_ERROR(
177  "FrankaStateController: Invalid or no joint_names parameters provided, aborting "
178  "controller init!");
179  return false;
180  }
181 
182  try {
183  franka_state_handle_ = std::make_unique<franka_hw::FrankaStateHandle>(
184  franka_state_interface_->getHandle(arm_id_ + "_robot"));
186  ROS_ERROR_STREAM("FrankaStateController: Exception getting franka state handle: " << ex.what());
187  return false;
188  }
189 
190  publisher_transforms_.init(root_node_handle, "/tf", 1);
191  publisher_franka_states_.init(controller_node_handle, "franka_states", 1);
192  publisher_joint_states_.init(controller_node_handle, "joint_states", 1);
193  publisher_joint_states_desired_.init(controller_node_handle, "joint_states_desired", 1);
194  publisher_external_wrench_.init(controller_node_handle, "F_ext", 1);
195 
196  {
197  std::lock_guard<realtime_tools::RealtimePublisher<sensor_msgs::JointState>> lock(
199  publisher_joint_states_.msg_.name.resize(joint_names_.size());
200  publisher_joint_states_.msg_.position.resize(robot_state_.q.size());
201  publisher_joint_states_.msg_.velocity.resize(robot_state_.dq.size());
202  publisher_joint_states_.msg_.effort.resize(robot_state_.tau_J.size());
203  }
204  {
205  std::lock_guard<realtime_tools::RealtimePublisher<sensor_msgs::JointState>> lock(
208  publisher_joint_states_desired_.msg_.position.resize(robot_state_.q_d.size());
209  publisher_joint_states_desired_.msg_.velocity.resize(robot_state_.dq_d.size());
211  }
212  {
213  std::lock_guard<realtime_tools::RealtimePublisher<tf2_msgs::TFMessage>> lock(
215  publisher_transforms_.msg_.transforms.resize(3);
216  tf::Quaternion quaternion(0.0, 0.0, 0.0, 1.0);
217  tf::Vector3 translation(0.0, 0.0, 0.05);
218  tf::Transform transform(quaternion, translation);
219  tf::StampedTransform stamped_transform(transform, ros::Time::now(), arm_id_ + "_link8",
220  arm_id_ + "_NE");
221  geometry_msgs::TransformStamped transform_message;
222  transformStampedTFToMsg(stamped_transform, transform_message);
223  publisher_transforms_.msg_.transforms[0] = transform_message;
224 
225  translation = tf::Vector3(0.0, 0.0, 0.0);
226  transform = tf::Transform(quaternion, translation);
227  stamped_transform =
228  tf::StampedTransform(transform, ros::Time::now(), arm_id_ + "_NE", arm_id_ + "_EE");
229  transformStampedTFToMsg(stamped_transform, transform_message);
230  publisher_transforms_.msg_.transforms[1] = transform_message;
231 
232  stamped_transform =
233  tf::StampedTransform(transform, ros::Time::now(), arm_id_ + "_EE", arm_id_ + "_K");
234  transformStampedTFToMsg(stamped_transform, transform_message);
235  publisher_transforms_.msg_.transforms[2] = transform_message;
236  }
237  {
238  std::lock_guard<realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped>> lock(
240  publisher_external_wrench_.msg_.header.frame_id = arm_id_ + "_K";
241  publisher_external_wrench_.msg_.wrench.force.x = 0.0;
242  publisher_external_wrench_.msg_.wrench.force.y = 0.0;
243  publisher_external_wrench_.msg_.wrench.force.z = 0.0;
244  publisher_external_wrench_.msg_.wrench.torque.x = 0.0;
245  publisher_external_wrench_.msg_.wrench.torque.y = 0.0;
246  publisher_external_wrench_.msg_.wrench.torque.z = 0.0;
247  }
248  return true;
249 }
250 
251 void FrankaStateController::update(const ros::Time& time, const ros::Duration& /* period */) {
252  if (trigger_publish_()) {
253  robot_state_ = franka_state_handle_->getRobotState();
254  publishFrankaStates(time);
255  publishTransforms(time);
256  publishExternalWrench(time);
257  publishJointStates(time);
259  }
260 }
261 
264  static_assert(
266  "Robot state Cartesian members do not have same size");
267  static_assert(sizeof(robot_state_.cartesian_collision) == sizeof(robot_state_.K_F_ext_hat_K),
268  "Robot state Cartesian members do not have same size");
269  static_assert(sizeof(robot_state_.cartesian_collision) == sizeof(robot_state_.O_F_ext_hat_K),
270  "Robot state Cartesian members do not have same size");
271  static_assert(sizeof(robot_state_.cartesian_collision) == sizeof(robot_state_.O_dP_EE_d),
272  "Robot state Cartesian members do not have same size");
273  static_assert(sizeof(robot_state_.cartesian_collision) == sizeof(robot_state_.O_dP_EE_c),
274  "Robot state Cartesian members do not have same size");
275  static_assert(sizeof(robot_state_.cartesian_collision) == sizeof(robot_state_.O_ddP_EE_c),
276  "Robot state Cartesian members do not have same size");
277  for (size_t i = 0; i < robot_state_.cartesian_collision.size(); i++) {
285  }
286 
287  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.q_d),
288  "Robot state joint members do not have same size");
289  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.dq),
290  "Robot state joint members do not have same size");
291  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.dq_d),
292  "Robot state joint members do not have same size");
293  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.ddq_d),
294  "Robot state joint members do not have same size");
295  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.tau_J),
296  "Robot state joint members do not have same size");
297  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.dtau_J),
298  "Robot state joint members do not have same size");
299  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.tau_J_d),
300  "Robot state joint members do not have same size");
301  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.theta),
302  "Robot state joint members do not have same size");
303  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.dtheta),
304  "Robot state joint members do not have same size");
305  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.joint_collision),
306  "Robot state joint members do not have same size");
307  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.joint_contact),
308  "Robot state joint members do not have same size");
309  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.tau_ext_hat_filtered),
310  "Robot state joint members do not have same size");
311  for (size_t i = 0; i < robot_state_.q.size(); i++) {
324  publisher_franka_states_.msg_.tau_ext_hat_filtered[i] = robot_state_.tau_ext_hat_filtered[i];
325  }
326 
327  static_assert(sizeof(robot_state_.elbow) == sizeof(robot_state_.elbow_d),
328  "Robot state elbow configuration members do not have same size");
329  static_assert(sizeof(robot_state_.elbow) == sizeof(robot_state_.elbow_c),
330  "Robot state elbow configuration members do not have same size");
331  static_assert(sizeof(robot_state_.elbow) == sizeof(robot_state_.delbow_c),
332  "Robot state elbow configuration members do not have same size");
333  static_assert(sizeof(robot_state_.elbow) == sizeof(robot_state_.ddelbow_c),
334  "Robot state elbow configuration members do not have same size");
335 
336  for (size_t i = 0; i < robot_state_.elbow.size(); i++) {
342  }
343 
344  static_assert(sizeof(robot_state_.O_T_EE) == sizeof(robot_state_.F_T_EE),
345  "Robot state transforms do not have same size");
346  static_assert(sizeof(robot_state_.O_T_EE) == sizeof(robot_state_.F_T_NE),
347  "Robot state transforms do not have same size");
348  static_assert(sizeof(robot_state_.O_T_EE) == sizeof(robot_state_.NE_T_EE),
349  "Robot state transforms do not have same size");
350  static_assert(sizeof(robot_state_.O_T_EE) == sizeof(robot_state_.EE_T_K),
351  "Robot state transforms do not have same size");
352  static_assert(sizeof(robot_state_.O_T_EE) == sizeof(robot_state_.O_T_EE_d),
353  "Robot state transforms do not have same size");
354  static_assert(sizeof(robot_state_.O_T_EE) == sizeof(robot_state_.O_T_EE_c),
355  "Robot state transforms do not have same size");
356  for (size_t i = 0; i < robot_state_.O_T_EE.size(); i++) {
359  publisher_franka_states_.msg_.F_T_NE[i] = robot_state_.F_T_NE[i];
360  publisher_franka_states_.msg_.NE_T_EE[i] = robot_state_.NE_T_EE[i];
364  }
368 
369  for (size_t i = 0; i < robot_state_.I_load.size(); i++) {
373  }
374 
375  for (size_t i = 0; i < robot_state_.F_x_Cload.size(); i++) {
379  }
380 #ifdef ENABLE_BASE_ACCELERATION
381  for (size_t i = 0; i < robot_state_.O_ddP_O.size(); i++) {
382  publisher_franka_states_.msg_.O_ddP_O[i] = robot_state_.O_ddP_O[i];
383  }
384 #else
385  publisher_franka_states_.msg_.O_ddP_O[2] = -9.81;
386 #endif
387 
389  publisher_franka_states_.msg_.control_command_success_rate =
391  publisher_franka_states_.msg_.current_errors = errorsToMessage(robot_state_.current_errors);
392  publisher_franka_states_.msg_.last_motion_errors =
393  errorsToMessage(robot_state_.last_motion_errors);
394 
395  switch (robot_state_.robot_mode) {
397  publisher_franka_states_.msg_.robot_mode = franka_msgs::FrankaState::ROBOT_MODE_OTHER;
398  break;
399 
401  publisher_franka_states_.msg_.robot_mode = franka_msgs::FrankaState::ROBOT_MODE_IDLE;
402  break;
403 
405  publisher_franka_states_.msg_.robot_mode = franka_msgs::FrankaState::ROBOT_MODE_MOVE;
406  break;
407 
409  publisher_franka_states_.msg_.robot_mode = franka_msgs::FrankaState::ROBOT_MODE_GUIDING;
410  break;
411 
413  publisher_franka_states_.msg_.robot_mode = franka_msgs::FrankaState::ROBOT_MODE_REFLEX;
414  break;
415 
417  publisher_franka_states_.msg_.robot_mode =
418  franka_msgs::FrankaState::ROBOT_MODE_USER_STOPPED;
419  break;
420 
422  publisher_franka_states_.msg_.robot_mode =
423  franka_msgs::FrankaState::ROBOT_MODE_AUTOMATIC_ERROR_RECOVERY;
424  break;
425  }
426 
428  publisher_franka_states_.msg_.header.stamp = time;
430  }
431 }
432 
435  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.dq),
436  "Robot state joint members do not have same size");
437  static_assert(sizeof(robot_state_.q) == sizeof(robot_state_.tau_J),
438  "Robot state joint members do not have same size");
439  for (size_t i = 0; i < robot_state_.q.size(); i++) {
441  publisher_joint_states_.msg_.position[i] = robot_state_.q[i];
442  publisher_joint_states_.msg_.velocity[i] = robot_state_.dq[i];
444  }
445  publisher_joint_states_.msg_.header.stamp = time;
448  }
450  static_assert(sizeof(robot_state_.q_d) == sizeof(robot_state_.dq_d),
451  "Robot state joint members do not have same size");
452  static_assert(sizeof(robot_state_.q_d) == sizeof(robot_state_.tau_J_d),
453  "Robot state joint members do not have same size");
454  for (size_t i = 0; i < robot_state_.q_d.size(); i++) {
459  }
460  publisher_joint_states_desired_.msg_.header.stamp = time;
463  }
464 }
465 
468  tf::StampedTransform stamped_transform(convertArrayToTf(robot_state_.F_T_NE), time,
469  arm_id_ + "_link8", arm_id_ + "_NE");
470  geometry_msgs::TransformStamped transform_message;
471  transformStampedTFToMsg(stamped_transform, transform_message);
472  publisher_transforms_.msg_.transforms[0] = transform_message;
473 
474  stamped_transform = tf::StampedTransform(convertArrayToTf(robot_state_.NE_T_EE), time,
475  arm_id_ + "_NE", arm_id_ + "_EE");
476  transformStampedTFToMsg(stamped_transform, transform_message);
477  publisher_transforms_.msg_.transforms[1] = transform_message;
478 
479  stamped_transform = tf::StampedTransform(convertArrayToTf(robot_state_.EE_T_K), time,
480  arm_id_ + "_EE", arm_id_ + "_K");
481  transformStampedTFToMsg(stamped_transform, transform_message);
482  publisher_transforms_.msg_.transforms[2] = transform_message;
484  }
485 }
486 
489  publisher_external_wrench_.msg_.header.frame_id = arm_id_ + "_K";
490  publisher_external_wrench_.msg_.header.stamp = time;
498  }
499 }
500 
501 } // namespace franka_control
502 
const bool & cartesian_motion_generator_joint_velocity_discontinuity
std::unique_ptr< franka_hw::FrankaStateHandle > franka_state_handle_
realtime_tools::RealtimePublisher< sensor_msgs::JointState > publisher_joint_states_desired_
const bool & cartesian_motion_generator_elbow_limit_violation
const bool & cartesian_motion_generator_joint_velocity_limits_violation
std::array< double, 16 > F_T_EE
const bool & force_control_safety_violation
std::array< double, 7 > dtau_J
std::array< double, 7 > tau_ext_hat_filtered
const bool & controller_torque_discontinuity
double toSec() const noexcept
std::array< double, 3 > F_x_Cload
const bool & joint_motion_generator_velocity_discontinuity
std::array< double, 3 > F_x_Ctotal
const bool & communication_constraints_violation
const bool & cartesian_position_motion_generator_start_pose_invalid
const bool & joint_reflex
Controller to publish the robot state as ROS topics.
const bool & self_collision_avoidance_violation
const bool & cartesian_motion_generator_start_elbow_invalid
const bool & cartesian_velocity_violation
void update(const ros::Time &time, const ros::Duration &period) override
Reads the current robot state from the franka_hw::FrankaStateInterface and publishes it...
std::array< double, 2 > elbow_c
#define ROS_ERROR(...)
const bool & cartesian_motion_generator_velocity_limits_violation
std::array< double, 7 > q_d
std::array< double, 6 > K_F_ext_hat_K
std::array< double, 6 > O_F_ext_hat_K
std::array< double, 16 > O_T_EE_d
const bool & joint_position_motion_generator_start_pose_invalid
std::array< double, 3 > F_x_Cee
std::array< double, 7 > joint_contact
const bool & joint_motion_generator_position_limits_violation
const bool & cartesian_motion_generator_joint_position_limits_violation
std::array< double, 2 > delbow_c
std::array< double, 7 > q
const bool & cartesian_motion_generator_velocity_discontinuity
const char * what() const noexcept override
const bool & cartesian_motion_generator_joint_acceleration_discontinuity
std::array< double, 7 > dtheta
const bool & joint_move_in_wrong_direction
const bool & max_path_pose_deviation_violation
bool getParam(const std::string &key, std::string &s) const
const bool & cartesian_position_limits_violation
const bool & cartesian_position_motion_generator_invalid_frame
const bool & cartesian_motion_generator_acceleration_discontinuity
std::array< double, 16 > O_T_EE_c
const bool & cartesian_velocity_profile_safety_violation
std::array< double, 7 > dq
const bool & joint_p2p_insufficient_torque_for_planning
const bool & max_goal_pose_deviation_violation
std::array< double, 16 > O_T_EE
def message(msg, args, kwargs)
const bool & joint_motion_generator_acceleration_discontinuity
std::array< double, 9 > I_load
std::array< double, 7 > dq_d
void publishExternalWrench(const ros::Time &time)
const bool & joint_position_limits_violation
const bool & force_controller_desired_force_tolerance_violation
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &root_node_handle, ros::NodeHandle &controller_node_handle) override
Initializes the controller with interfaces and publishers.
std::array< double, 6 > O_ddP_EE_c
realtime_tools::RealtimePublisher< sensor_msgs::JointState > publisher_joint_states_
std::array< double, 6 > O_dP_EE_c
std::array< double, 2 > ddelbow_c
std::array< double, 7 > joint_collision
void init(const ros::NodeHandle &node, const std::string &topic, int queue_size, bool latched=false)
const bool & power_limit_violation
std::array< double, 7 > ddq_d
#define ROS_INFO_STREAM(args)
realtime_tools::RealtimePublisher< tf2_msgs::TFMessage > publisher_transforms_
std::array< double, 7 > tau_J_d
const bool & cartesian_reflex
std::array< double, 9 > I_total
std::array< double, 2 > elbow_d
std::array< double, 6 > cartesian_contact
RobotMode robot_mode
static Time now()
const bool & joint_motion_generator_velocity_limits_violation
const bool & instability_detected
#define ROS_ERROR_STREAM(args)
std::array< double, 9 > I_ee
franka_hw::FrankaStateInterface * franka_state_interface_
double control_command_success_rate
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
const bool & joint_velocity_violation
realtime_tools::RealtimePublisher< franka_msgs::FrankaState > publisher_franka_states_
const bool & cartesian_motion_generator_elbow_sign_inconsistent
std::array< double, 6 > O_dP_EE_d
std::array< double, 7 > tau_J
const bool & start_elbow_sign_inconsistent
const bool & tau_j_range_violation
std::array< double, 2 > elbow
realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > publisher_external_wrench_
std::array< double, 16 > EE_T_K
std::array< double, 6 > cartesian_collision
std::array< double, 7 > theta


franka_control
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 03:05:59