cartesian_velocity_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 <array>
6 #include <cmath>
7 #include <memory>
8 #include <string>
9 
14 #include <ros/ros.h>
15 
17 
19  ros::NodeHandle& node_handle) {
20  std::string arm_id;
21  if (!node_handle.getParam("arm_id", arm_id)) {
22  ROS_ERROR("CartesianVelocityExampleController: Could not get parameter arm_id");
23  return false;
24  }
25 
28  if (velocity_cartesian_interface_ == nullptr) {
29  ROS_ERROR(
30  "CartesianVelocityExampleController: Could not get Cartesian velocity interface from "
31  "hardware");
32  return false;
33  }
34  try {
35  velocity_cartesian_handle_ = std::make_unique<franka_hw::FrankaCartesianVelocityHandle>(
36  velocity_cartesian_interface_->getHandle(arm_id + "_robot"));
39  "CartesianVelocityExampleController: 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("CartesianVelocityExampleController: 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  "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>` "
59  "first.");
60  return false;
61  }
62  }
65  "CartesianVelocityExampleController: Exception getting state handle: " << e.what());
66  return false;
67  }
68 
69  return true;
70 }
71 
74 }
75 
77  const ros::Duration& period) {
78  elapsed_time_ += period;
79 
80  double time_max = 4.0;
81  double v_max = 0.05;
82  double angle = M_PI / 4.0;
83  double cycle = std::floor(
84  pow(-1.0, (elapsed_time_.toSec() - std::fmod(elapsed_time_.toSec(), time_max)) / time_max));
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}};
89  velocity_cartesian_handle_->setCommand(command);
90 }
91 
93  // WARNING: DO NOT SEND ZERO VELOCITIES HERE AS IN CASE OF ABORTING DURING MOTION
94  // A JUMP TO ZERO WILL BE COMMANDED PUTTING HIGH LOADS ON THE ROBOT. LET THE DEFAULT
95  // BUILT-IN STOPPING BEHAVIOR SLOW DOWN THE ROBOT.
96 }
97 
98 } // namespace franka_example_controllers
99 
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
std::unique_ptr< franka_hw::FrankaCartesianVelocityHandle > velocity_cartesian_handle_
std::string arm_id
void update(const ros::Time &, const ros::Duration &period) override
v
#define M_PI
#define M_PI_2
ROSLIB_DECL std::string command(const std::string &cmd)
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(...)


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