22 ROS_ERROR(
"CartesianVelocityExampleController: Could not get parameter arm_id");
30 "CartesianVelocityExampleController: Could not get Cartesian velocity interface from "
39 "CartesianVelocityExampleController: Exception getting Cartesian handle: " << e.
what());
44 if (state_interface ==
nullptr) {
45 ROS_ERROR(
"CartesianVelocityExampleController: 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 "CartesianVelocityExampleController: Robot is not in the expected starting position "
57 "for running this example. Run `roslaunch franka_example_controllers "
58 "move_to_start.launch robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` "
65 "CartesianVelocityExampleController: Exception getting state handle: " << e.
what());
80 double time_max = 4.0;
82 double angle = M_PI / 4.0;
83 double cycle = std::floor(
85 double v = cycle * v_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max *
elapsed_time_.
toSec()));
86 double v_x = std::cos(
angle) * v;
87 double v_z = -std::sin(
angle) * v;
88 std::array<double, 6>
command = {{v_x, 0.0, v_z, 0.0, 0.0, 0.0}};