23 "CartesianPoseExampleController: Could not get Cartesian Pose " 24 "interface from hardware");
29 if (!node_handle.
getParam(
"arm_id", arm_id)) {
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;
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
virtual const char * what() const
franka_hw::FrankaPoseCartesianInterface * cartesian_pose_interface_
void starting(const ros::Time &) override
std::array< double, 16 > initial_pose_
ros::Duration elapsed_time_
std::unique_ptr< franka_hw::FrankaCartesianPoseHandle > cartesian_pose_handle_
bool getParam(const std::string &key, std::string &s) const
void update(const ros::Time &, const ros::Duration &period) override
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_ERROR_STREAM(args)