cartesian_pose_example_controller.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
4 
5 #include <cmath>
6 #include <memory>
7 #include <stdexcept>
8 #include <string>
9 
14 #include <ros/ros.h>
15 
17 
19  ros::NodeHandle& node_handle) {
21  if (cartesian_pose_interface_ == nullptr) {
22  ROS_ERROR(
23  "CartesianPoseExampleController: Could not get Cartesian Pose "
24  "interface from hardware");
25  return false;
26  }
27 
28  std::string arm_id;
29  if (!node_handle.getParam("arm_id", arm_id)) {
30  ROS_ERROR("CartesianPoseExampleController: Could not get parameter arm_id");
31  return false;
32  }
33 
34  try {
35  cartesian_pose_handle_ = std::make_unique<franka_hw::FrankaCartesianPoseHandle>(
36  cartesian_pose_interface_->getHandle(arm_id + "_robot"));
39  "CartesianPoseExampleController: Exception getting Cartesian handle: " << e.what());
40  return false;
41  }
42 
43  auto state_interface = robot_hardware->get<franka_hw::FrankaStateInterface>();
44  if (state_interface == nullptr) {
45  ROS_ERROR("CartesianPoseExampleController: Could not get state interface from hardware");
46  return false;
47  }
48 
49  try {
50  auto state_handle = state_interface->getHandle(arm_id + "_robot");
51 
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.");
59  return false;
60  }
61  }
64  "CartesianPoseExampleController: Exception getting state handle: " << e.what());
65  return false;
66  }
67 
68  return true;
69 }
70 
72  initial_pose_ = cartesian_pose_handle_->getRobotState().O_T_EE_d;
74 }
75 
77  const ros::Duration& period) {
78  elapsed_time_ += period;
79 
80  double radius = 0.3;
81  double angle = M_PI / 4 * (1 - std::cos(M_PI / 5.0 * elapsed_time_.toSec()));
82  double delta_x = radius * std::sin(angle);
83  double delta_z = radius * (std::cos(angle) - 1);
84  std::array<double, 16> new_pose = initial_pose_;
85  new_pose[12] -= delta_x;
86  new_pose[14] -= delta_z;
87  cartesian_pose_handle_->setCommand(new_pose);
88 }
89 
90 } // namespace franka_example_controllers
91 
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
std::string arm_id
#define M_PI
#define M_PI_2
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)
#define ROS_ERROR(...)


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:17