23 "CartesianPoseExampleController: Could not get Cartesian Pose "
24 "interface from hardware");
30 ROS_ERROR(
"CartesianPoseExampleController: Could not get parameter arm_id");
39 "CartesianPoseExampleController: Exception getting Cartesian handle: " << e.
what());
44 if (state_interface ==
nullptr) {
45 ROS_ERROR(
"CartesianPoseExampleController: Could not get state interface from hardware");
50 auto state_handle = state_interface->getHandle(
arm_id +
"_robot");
52 std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
53 for (
size_t i = 0; i < q_start.size(); i++) {
54 if (std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) {
56 "CartesianPoseExampleController: Robot is not in the expected starting position for "
57 "running this example. Run `roslaunch franka_example_controllers move_to_start.launch "
58 "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first.");
64 "CartesianPoseExampleController: Exception getting state handle: " << e.
what());
82 double delta_x = radius * std::sin(
angle);
83 double delta_z = radius * (std::cos(
angle) - 1);
85 new_pose[12] -= delta_x;
86 new_pose[14] -= delta_z;