franka_hw.h
libfrankaのヘッダファイルを使用
#include <franka/control_types.h>
#include <franka/duration.h>
#include <franka/rate_limiting.h>
#include <franka/robot.h>
#include <franka/robot_state.h>
namespace franka_hw {
class FrankaHW : public hardware_interface::RobotHW {
franka::RobotState robot_state_libfranka_{};
franka::JointPositions position_joint_command_libfranka_;
franka::JointVelocities velocity_joint_command_libfranka_;
franka::Torques effort_joint_command_libfranka_;
franka::CartesianPose pose_cartesian_command_libfranka_;
franka::CartesianVelocities velocity_cartesian_command_libfranka_;
std::unique_ptr<franka::Robot> robot_;
};
} // namespace franka_hw
franka_hw.cpp
#include <franka_hw/franka_hw.h>
void FrankaHW::connect() {
if (!robot_) {
robot_ = std::make_unique<franka::Robot>(robot_ip_, realtime_config_);
robot_->setCollisionBehavior(collision_config_.lower_torque_thresholds_acceleration,
collision_config_.upper_torque_thresholds_acceleration,
collision_config_.lower_torque_thresholds_nominal,
collision_config_.upper_torque_thresholds_nominal,
collision_config_.lower_force_thresholds_acceleration,
collision_config_.upper_force_thresholds_acceleration,
collision_config_.lower_force_thresholds_nominal,
collision_config_.upper_force_thresholds_nominal);
}
}
void FrankaHW::initRobot() {
connect();
model_ = std::make_unique<franka_hw::Model>(robot_->loadModel());
update(robot_->readOnce());
}