22 ROS_ERROR(
"ElbowExampleController: Could not get Cartesian Pose interface from hardware");
27 if (!node_handle.
getParam(
"arm_id", arm_id)) {
28 ROS_ERROR(
"ElbowExampleController: Could not get parameter arm_id");
41 if (state_interface ==
nullptr) {
42 ROS_ERROR(
"ElbowExampleController: Could not get state interface from hardware");
47 auto state_handle = state_interface->getHandle(arm_id +
"_robot");
49 std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
50 for (
size_t i = 0; i < q_start.size(); i++) {
51 if (std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) {
53 "ElbowExampleController: Robot is not in the expected starting position for " 54 "running this example. Run `roslaunch franka_example_controllers move_to_start.launch " 55 "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first.");
ros::Duration elapsed_time_
std::array< double, 2 > initial_elbow_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void starting(const ros::Time &) override
const char * what() const noexcept override
std::unique_ptr< franka_hw::FrankaCartesianPoseHandle > cartesian_pose_handle_
bool getParam(const std::string &key, std::string &s) const
franka_hw::FrankaPoseCartesianInterface * cartesian_pose_interface_
std::array< double, 16 > initial_pose_
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
void update(const ros::Time &, const ros::Duration &period) override