franka_hw_sim.h
Go to the documentation of this file.
1 #pragma once
2 
4 #include <franka/robot_state.h>
6 #include <franka_gazebo/joint.h>
10 #include <franka_hw/model_base.h>
11 #include <franka_msgs/ErrorRecoveryAction.h>
17 #include <ros/ros.h>
18 #include <urdf/model.h>
19 #include <boost/optional.hpp>
20 #include <boost_sml/sml.hpp>
21 #include <cmath>
22 #include <gazebo/common/common.hh>
23 #include <gazebo/physics/physics.hh>
24 #include <map>
25 #include <memory>
26 #include <mutex>
27 
28 namespace franka_gazebo {
29 
30 const double kDefaultTauExtLowpassFilter = 1.0; // no filtering per default of tau_ext_hat_filtered
31 
51  public:
55  FrankaHWSim();
56 
69  bool initSim(const std::string& robot_namespace,
70  ros::NodeHandle model_nh,
71  gazebo::physics::ModelPtr parent,
72  const urdf::Model* const urdf,
73  std::vector<transmission_interface::TransmissionInfo> transmissions) override;
74 
87  void readSim(ros::Time time, ros::Duration period) override;
88 
99  void writeSim(ros::Time time, ros::Duration period) override;
100 
106  void eStopActive(const bool active) override;
107 
113  void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
114  const std::list<hardware_interface::ControllerInfo>& stop_list) override;
115 
122  bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
123  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/) override;
124 
125  private:
128 
129  std::unique_ptr<ControllerVerifier> verifier_;
130 
131  std::array<double, 3> gravity_earth_;
132 
133  std::string arm_id_;
134  gazebo::physics::ModelPtr robot_;
135  std::map<std::string, std::shared_ptr<franka_gazebo::Joint>> joints_;
136 
143 
144  boost::sml::sm<franka_gazebo::StateMachine, boost::sml::thread_safe<std::mutex>> sm_;
145  franka::RobotState robot_state_;
146  std::unique_ptr<franka_hw::ModelBase> model_;
147 
149 
158  std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>> action_recovery_;
159 
160  std::vector<double> lower_force_thresholds_nominal_;
161  std::vector<double> upper_force_thresholds_nominal_;
162 
163  void initJointStateHandle(const std::shared_ptr<franka_gazebo::Joint>& joint);
164  void initEffortCommandHandle(const std::shared_ptr<franka_gazebo::Joint>& joint);
165  void initPositionCommandHandle(const std::shared_ptr<franka_gazebo::Joint>& joint);
166  void initVelocityCommandHandle(const std::shared_ptr<franka_gazebo::Joint>& joint);
167  void initFrankaStateHandle(const std::string& robot,
168  const urdf::Model& urdf,
169  const transmission_interface::TransmissionInfo& transmission);
170  void initFrankaModelHandle(const std::string& robot,
171  const urdf::Model& urdf,
172  const transmission_interface::TransmissionInfo& transmission,
173  double singularity_threshold);
174  void initServices(ros::NodeHandle& nh);
175 
176  void restartControllers();
177 
178  void updateRobotState(ros::Time time);
180 
181  bool readParameters(const ros::NodeHandle& nh, const urdf::Model& urdf);
182 
183  void guessEndEffector(const ros::NodeHandle& nh, const urdf::Model& urdf);
184 
185  static double positionControl(Joint& joint, double setpoint, const ros::Duration& period);
186  static double velocityControl(Joint& joint, double setpoint, const ros::Duration& period);
187 
188  template <int N>
189  std::array<double, N> readArray(std::string param, std::string name = "") {
190  std::array<double, N> x;
191 
192  std::istringstream iss(param);
193  std::vector<std::string> values{std::istream_iterator<std::string>{iss},
194  std::istream_iterator<std::string>{}};
195  if (values.size() != N) {
196  throw std::invalid_argument("Expected parameter '" + name + "' to have exactely " +
197  std::to_string(N) + " numbers separated by spaces, but found " +
198  std::to_string(values.size()));
199  }
200  std::transform(values.begin(), values.end(), x.begin(),
201  [](std::string v) -> double { return std::stod(v); });
202  return x;
203  }
204 
212  static Eigen::Matrix3d skewMatrix(const Eigen::Vector3d& vec) {
213  Eigen::Matrix3d vec_hat;
214  // clang-format off
215  vec_hat <<
216  0, -vec(2), vec(1),
217  vec(2), 0, -vec(0),
218  -vec(1), vec(0), 0;
219  // clang-format on
220  return vec_hat;
221  }
222 
238  static Eigen::Matrix3d shiftInertiaTensor(Eigen::Matrix3d I, double m, Eigen::Vector3d p) {
239  Eigen::Matrix3d P = skewMatrix(p);
240  Eigen::Matrix3d Ip = I + m * P.transpose() * P;
241  return Ip;
242  }
243 
244  void forControlledJoint(
245  const std::list<hardware_interface::ControllerInfo>& controllers,
246  const std::function<void(franka_gazebo::Joint& joint, const ControlMethod&)>& f);
247 };
248 
249 } // namespace franka_gazebo
franka_gazebo::FrankaHWSim::restartControllers
void restartControllers()
Definition: franka_hw_sim.cpp:402
franka_gazebo::FrankaHWSim::forControlledJoint
void forControlledJoint(const std::list< hardware_interface::ControllerInfo > &controllers, const std::function< void(franka_gazebo::Joint &joint, const ControlMethod &)> &f)
Definition: franka_hw_sim.cpp:744
franka_gazebo
Definition: controller_verifier.h:8
franka_gazebo::FrankaHWSim::sm_
boost::sml::sm< franka_gazebo::StateMachine, boost::sml::thread_safe< std::mutex > > sm_
Definition: franka_hw_sim.h:144
franka_gazebo::FrankaHWSim::service_controller_switch_
ros::ServiceClient service_controller_switch_
Definition: franka_hw_sim.h:157
ros::Publisher
franka_gazebo::FrankaHWSim::verifier_
std::unique_ptr< ControllerVerifier > verifier_
Definition: franka_hw_sim.h:129
controller_verifier.h
hardware_interface::JointStateInterface
franka_gazebo::FrankaHWSim::eStopActive
void eStopActive(const bool active) override
Set the emergency stop state (not yet implemented)
Definition: franka_hw_sim.cpp:509
franka_gazebo::FrankaHWSim::pji_
hardware_interface::PositionJointInterface pji_
Definition: franka_hw_sim.h:139
ros.h
franka_gazebo::FrankaHWSim::positionControl
static double positionControl(Joint &joint, double setpoint, const ros::Duration &period)
Definition: franka_hw_sim.cpp:440
franka_gazebo::FrankaHWSim::tau_ext_lowpass_filter_
double tau_ext_lowpass_filter_
Definition: franka_hw_sim.h:148
franka_gazebo::FrankaHWSim::jsi_
hardware_interface::JointStateInterface jsi_
Definition: franka_hw_sim.h:137
franka_gazebo::FrankaHWSim::vji_
hardware_interface::VelocityJointInterface vji_
Definition: franka_hw_sim.h:140
franka_gazebo::FrankaHWSim::fsi_
franka_hw::FrankaStateInterface fsi_
Definition: franka_hw_sim.h:141
simple_action_server.h
franka_gazebo::FrankaHWSim::service_controller_list_
ros::ServiceClient service_controller_list_
Definition: franka_hw_sim.h:156
franka_gazebo::FrankaHWSim::initFrankaModelHandle
void initFrankaModelHandle(const std::string &robot, const urdf::Model &urdf, const transmission_interface::TransmissionInfo &transmission, double singularity_threshold)
Definition: franka_hw_sim.cpp:280
urdf::Model
franka_gazebo::FrankaHWSim::readArray
std::array< double, N > readArray(std::string param, std::string name="")
Definition: franka_hw_sim.h:189
gazebo_ros_control::RobotHWSim
franka_gazebo::FrankaHWSim::arm_id_
std::string arm_id_
Definition: franka_hw_sim.h:133
franka_gazebo::FrankaHWSim::initEffortCommandHandle
void initEffortCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
Definition: franka_hw_sim.cpp:238
franka_gazebo::FrankaHWSim::service_user_stop_
ros::ServiceServer service_user_stop_
Definition: franka_hw_sim.h:155
franka_gazebo::FrankaHWSim::readParameters
bool readParameters(const ros::NodeHandle &nh, const urdf::Model &urdf)
Definition: franka_hw_sim.cpp:511
franka_gazebo::FrankaHWSim::service_set_load_
ros::ServiceServer service_set_load_
Definition: franka_hw_sim.h:153
joint.h
ros::ServiceServer
class_list_macros.h
franka_gazebo::FrankaHWSim::upper_force_thresholds_nominal_
std::vector< double > upper_force_thresholds_nominal_
Definition: franka_hw_sim.h:161
franka_gazebo::FrankaHWSim::initFrankaStateHandle
void initFrankaStateHandle(const std::string &robot, const urdf::Model &urdf, const transmission_interface::TransmissionInfo &transmission)
Definition: franka_hw_sim.cpp:253
robot_hw_sim.h
hardware_interface::VelocityJointInterface
franka_gazebo::FrankaHWSim::updateRobotStateDynamics
void updateRobotStateDynamics()
Definition: franka_hw_sim.cpp:626
franka_gazebo::FrankaHWSim::skewMatrix
static Eigen::Matrix3d skewMatrix(const Eigen::Vector3d &vec)
Helper function for generating a skew symmetric matrix for a given input vector such that: .
Definition: franka_hw_sim.h:212
franka_gazebo::FrankaHWSim::lower_force_thresholds_nominal_
std::vector< double > lower_force_thresholds_nominal_
Definition: franka_hw_sim.h:160
franka_gazebo::FrankaHWSim::initSim
bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent, const urdf::Model *const urdf, std::vector< transmission_interface::TransmissionInfo > transmissions) override
Initialize the simulated robot hardware and parse all supported transmissions.
Definition: franka_hw_sim.cpp:32
joint_command_interface.h
franka_gazebo::FrankaHWSim
A custom implementation of a gazebo_ros_control plugin, which is able to simulate franka interfaces i...
Definition: franka_hw_sim.h:50
statemachine.h
franka_gazebo::FrankaHWSim::doSwitch
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
Switches the control mode of the robot arm.
Definition: franka_hw_sim.cpp:726
franka_gazebo::FrankaHWSim::joints_
std::map< std::string, std::shared_ptr< franka_gazebo::Joint > > joints_
Definition: franka_hw_sim.h:135
name
name
model.h
franka_hw::FrankaStateInterface
franka_gazebo::FrankaHWSim::FrankaHWSim
FrankaHWSim()
Create a new FrankaHWSim instance.
Definition: franka_hw_sim.cpp:30
franka_gazebo::FrankaHWSim::shiftInertiaTensor
static Eigen::Matrix3d shiftInertiaTensor(Eigen::Matrix3d I, double m, Eigen::Vector3d p)
Shift the moment of inertia tensor by a given offset.
Definition: franka_hw_sim.h:238
hardware_interface::EffortJointInterface
ros::ServiceClient
franka_gazebo::FrankaHWSim::robot_initialized_pub_
ros::Publisher robot_initialized_pub_
Definition: franka_hw_sim.h:150
franka_gazebo::FrankaHWSim::service_set_ee_
ros::ServiceServer service_set_ee_
Definition: franka_hw_sim.h:151
franka_gazebo::FrankaHWSim::robot_
gazebo::physics::ModelPtr robot_
Definition: franka_hw_sim.h:134
franka_gazebo::FrankaHWSim::readSim
void readSim(ros::Time time, ros::Duration period) override
Fetch data from the Gazebo simulation and pass it on to the hardware interfaces.
Definition: franka_hw_sim.cpp:432
franka_gazebo::FrankaHWSim::updateRobotState
void updateRobotState(ros::Time time)
Definition: franka_hw_sim.cpp:638
franka_gazebo::FrankaHWSim::initServices
void initServices(ros::NodeHandle &nh)
Definition: franka_hw_sim.cpp:332
x
x
franka_gazebo::FrankaHWSim::prepareSwitch
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &) override
Check (in non-realtime) if given controllers could be started and stopped from the current state of t...
Definition: franka_hw_sim.cpp:718
franka_gazebo::FrankaHWSim::guessEndEffector
void guessEndEffector(const ros::NodeHandle &nh, const urdf::Model &urdf)
Definition: franka_hw_sim.cpp:564
franka_state_interface.h
franka_gazebo::FrankaHWSim::robot_state_
franka::RobotState robot_state_
Definition: franka_hw_sim.h:145
franka_hw::FrankaModelInterface
joint_state_interface.h
franka_gazebo::FrankaHWSim::velocityControl
static double velocityControl(Joint &joint, double setpoint, const ros::Duration &period)
Definition: franka_hw_sim.cpp:464
franka_gazebo::FrankaHWSim::action_recovery_
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > action_recovery_
Definition: franka_hw_sim.h:158
ros::Time
values
std::vector< double > values
franka_model_interface.h
urdf
franka_gazebo::FrankaHWSim::eji_
hardware_interface::EffortJointInterface eji_
Definition: franka_hw_sim.h:138
franka_gazebo::FrankaHWSim::service_set_k_
ros::ServiceServer service_set_k_
Definition: franka_hw_sim.h:152
franka_gazebo::FrankaHWSim::initVelocityCommandHandle
void initVelocityCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
Definition: franka_hw_sim.cpp:248
model_base.h
franka_gazebo::FrankaHWSim::initJointStateHandle
void initJointStateHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
Definition: franka_hw_sim.cpp:233
franka_gazebo::kDefaultTauExtLowpassFilter
const double kDefaultTauExtLowpassFilter
Definition: franka_hw_sim.h:30
franka_gazebo::ControlMethod
ControlMethod
Specifies the current control method of the joint.
Definition: joint.h:17
franka_gazebo::FrankaHWSim::robot_initialized_
bool robot_initialized_
If gazebo::Joint::GetForceTorque() yielded already a non-zero value.
Definition: franka_hw_sim.h:127
franka_gazebo::FrankaHWSim::model_
std::unique_ptr< franka_hw::ModelBase > model_
Definition: franka_hw_sim.h:146
franka_gazebo::FrankaHWSim::gravity_earth_
std::array< double, 3 > gravity_earth_
Definition: franka_hw_sim.h:131
franka_gazebo::Joint
A data container holding all relevant information about a robotic joint.
Definition: joint.h:25
franka_gazebo::FrankaHWSim::writeSim
void writeSim(ros::Time time, ros::Duration period) override
Pass the data send from controllers via the hardware interfaces onto the simulation.
Definition: franka_hw_sim.cpp:470
franka_gazebo::FrankaHWSim::initPositionCommandHandle
void initPositionCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
Definition: franka_hw_sim.cpp:243
hardware_interface::PositionJointInterface
sml.hpp
ros::Duration
transmission_interface::TransmissionInfo
franka_gazebo::FrankaHWSim::fmi_
franka_hw::FrankaModelInterface fmi_
Definition: franka_hw_sim.h:142
ros::NodeHandle
franka_gazebo::FrankaHWSim::service_collision_behavior_
ros::ServiceServer service_collision_behavior_
Definition: franka_hw_sim.h:154
param
param
hardware_resource_manager.h


franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:28