elbow_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("ElbowExampleController: Could not get Cartesian Pose interface from hardware");
23  return false;
24  }
25 
26  std::string arm_id;
27  if (!node_handle.getParam("arm_id", arm_id)) {
28  ROS_ERROR("ElbowExampleController: Could not get parameter arm_id");
29  return false;
30  }
31 
32  try {
33  cartesian_pose_handle_ = std::make_unique<franka_hw::FrankaCartesianPoseHandle>(
34  cartesian_pose_interface_->getHandle(arm_id + "_robot"));
36  ROS_ERROR_STREAM("ElbowExampleController: Exception getting Cartesian handle: " << e.what());
37  return false;
38  }
39 
40  auto state_interface = robot_hardware->get<franka_hw::FrankaStateInterface>();
41  if (state_interface == nullptr) {
42  ROS_ERROR("ElbowExampleController: Could not get state interface from hardware");
43  return false;
44  }
45 
46  try {
47  auto state_handle = state_interface->getHandle(arm_id + "_robot");
48 
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.");
56  return false;
57  }
58  }
60  ROS_ERROR_STREAM("ElbowExampleController: Exception getting state handle: " << e.what());
61  return false;
62  }
63 
64  return true;
65 }
66 
68  initial_pose_ = cartesian_pose_handle_->getRobotState().O_T_EE_d;
69  initial_elbow_ = cartesian_pose_handle_->getRobotState().elbow_d;
71 }
72 
73 void ElbowExampleController::update(const ros::Time& /* time */, const ros::Duration& period) {
74  elapsed_time_ += period;
75 
76  double angle = M_PI / 10.0 * (1.0 - std::cos(M_PI / 5.0 * elapsed_time_.toSec()));
77  auto elbow = initial_elbow_;
78  elbow[0] += angle;
79 
80  cartesian_pose_handle_->setCommand(initial_pose_, elbow);
81 }
82 
83 } // namespace franka_example_controllers
84 
std::string arm_id
#define M_PI
#define M_PI_2
std::unique_ptr< franka_hw::FrankaCartesianPoseHandle > cartesian_pose_handle_
franka_hw::FrankaPoseCartesianInterface * cartesian_pose_interface_
bool getParam(const std::string &key, std::string &s) const
PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager, moveit_controller_manager::MoveItControllerManager)
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
void update(const ros::Time &, const ros::Duration &period) override


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