Go to the documentation of this file.
4 #include <franka/robot_state.h>
11 #include <franka_msgs/ErrorRecoveryAction.h>
19 #include <boost/optional.hpp>
22 #include <gazebo/common/common.hh>
23 #include <gazebo/physics/physics.hh>
69 bool initSim(
const std::string& robot_namespace,
71 gazebo::physics::ModelPtr parent,
73 std::vector<transmission_interface::TransmissionInfo> transmissions)
override;
113 void doSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list,
114 const std::list<hardware_interface::ControllerInfo>& stop_list)
override;
122 bool prepareSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list,
123 const std::list<hardware_interface::ControllerInfo>& )
override;
135 std::map<std::string, std::shared_ptr<franka_gazebo::Joint>>
joints_;
144 boost::sml::sm<franka_gazebo::StateMachine, boost::sml::thread_safe<std::mutex>>
sm_;
146 std::unique_ptr<franka_hw::ModelBase>
model_;
158 std::unique_ptr<actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction>>
action_recovery_;
173 double singularity_threshold);
189 std::array<double, N>
readArray(std::string param, std::string name =
"") {
190 std::array<double, N>
x;
192 std::istringstream iss(
param);
193 std::vector<std::string>
values{std::istream_iterator<std::string>{iss},
194 std::istream_iterator<std::string>{}};
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()));
201 [](std::string v) ->
double { return std::stod(v); });
212 static Eigen::Matrix3d
skewMatrix(
const Eigen::Vector3d& vec) {
213 Eigen::Matrix3d vec_hat;
240 Eigen::Matrix3d Ip = I + m * P.transpose() * P;
245 const std::list<hardware_interface::ControllerInfo>& controllers,
void restartControllers()
void forControlledJoint(const std::list< hardware_interface::ControllerInfo > &controllers, const std::function< void(franka_gazebo::Joint &joint, const ControlMethod &)> &f)
boost::sml::sm< franka_gazebo::StateMachine, boost::sml::thread_safe< std::mutex > > sm_
ros::ServiceClient service_controller_switch_
std::unique_ptr< ControllerVerifier > verifier_
void eStopActive(const bool active) override
Set the emergency stop state (not yet implemented)
hardware_interface::PositionJointInterface pji_
static double positionControl(Joint &joint, double setpoint, const ros::Duration &period)
double tau_ext_lowpass_filter_
hardware_interface::JointStateInterface jsi_
hardware_interface::VelocityJointInterface vji_
franka_hw::FrankaStateInterface fsi_
ros::ServiceClient service_controller_list_
void initFrankaModelHandle(const std::string &robot, const urdf::Model &urdf, const transmission_interface::TransmissionInfo &transmission, double singularity_threshold)
std::array< double, N > readArray(std::string param, std::string name="")
void initEffortCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
ros::ServiceServer service_user_stop_
bool readParameters(const ros::NodeHandle &nh, const urdf::Model &urdf)
ros::ServiceServer service_set_load_
std::vector< double > upper_force_thresholds_nominal_
void initFrankaStateHandle(const std::string &robot, const urdf::Model &urdf, const transmission_interface::TransmissionInfo &transmission)
void updateRobotStateDynamics()
static Eigen::Matrix3d skewMatrix(const Eigen::Vector3d &vec)
Helper function for generating a skew symmetric matrix for a given input vector such that: .
std::vector< double > lower_force_thresholds_nominal_
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.
A custom implementation of a gazebo_ros_control plugin, which is able to simulate franka interfaces i...
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.
std::map< std::string, std::shared_ptr< franka_gazebo::Joint > > joints_
FrankaHWSim()
Create a new FrankaHWSim instance.
static Eigen::Matrix3d shiftInertiaTensor(Eigen::Matrix3d I, double m, Eigen::Vector3d p)
Shift the moment of inertia tensor by a given offset.
ros::Publisher robot_initialized_pub_
ros::ServiceServer service_set_ee_
gazebo::physics::ModelPtr robot_
void readSim(ros::Time time, ros::Duration period) override
Fetch data from the Gazebo simulation and pass it on to the hardware interfaces.
void updateRobotState(ros::Time time)
void initServices(ros::NodeHandle &nh)
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...
void guessEndEffector(const ros::NodeHandle &nh, const urdf::Model &urdf)
franka::RobotState robot_state_
static double velocityControl(Joint &joint, double setpoint, const ros::Duration &period)
std::unique_ptr< actionlib::SimpleActionServer< franka_msgs::ErrorRecoveryAction > > action_recovery_
std::vector< double > values
hardware_interface::EffortJointInterface eji_
ros::ServiceServer service_set_k_
void initVelocityCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
void initJointStateHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
const double kDefaultTauExtLowpassFilter
ControlMethod
Specifies the current control method of the joint.
bool robot_initialized_
If gazebo::Joint::GetForceTorque() yielded already a non-zero value.
std::unique_ptr< franka_hw::ModelBase > model_
std::array< double, 3 > gravity_earth_
A data container holding all relevant information about a robotic joint.
void writeSim(ros::Time time, ros::Duration period) override
Pass the data send from controllers via the hardware interfaces onto the simulation.
void initPositionCommandHandle(const std::shared_ptr< franka_gazebo::Joint > &joint)
franka_hw::FrankaModelInterface fmi_
ros::ServiceServer service_collision_behavior_
franka_gazebo
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:28