joint_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 <cmath>
6 
11 #include <ros/ros.h>
12 
14 
16  ros::NodeHandle& node_handle) {
18  if (velocity_joint_interface_ == nullptr) {
19  ROS_ERROR(
20  "JointVelocityExampleController: Error getting velocity joint interface from hardware!");
21  return false;
22  }
23  std::vector<std::string> joint_names;
24  if (!node_handle.getParam("joint_names", joint_names)) {
25  ROS_ERROR("JointVelocityExampleController: Could not parse joint names");
26  }
27  if (joint_names.size() != 7) {
28  ROS_ERROR_STREAM("JointVelocityExampleController: Wrong number of joint names, got "
29  << joint_names.size() << " instead of 7 names!");
30  return false;
31  }
32  velocity_joint_handles_.resize(7);
33  for (size_t i = 0; i < 7; ++i) {
34  try {
38  "JointVelocityExampleController: Exception getting joint handles: " << ex.what());
39  return false;
40  }
41  }
42 
43  auto state_interface = robot_hardware->get<franka_hw::FrankaStateInterface>();
44  if (state_interface == nullptr) {
45  ROS_ERROR("JointVelocityExampleController: Could not get state interface from hardware");
46  return false;
47  }
48 
49  try {
50  auto state_handle = state_interface->getHandle("panda_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  "JointVelocityExampleController: 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  "JointVelocityExampleController: Exception getting state handle: " << e.what());
65  return false;
66  }
67 
68  return true;
69 }
70 
73 }
74 
76  const ros::Duration& period) {
77  elapsed_time_ += period;
78 
79  ros::Duration time_max(8.0);
80  double omega_max = 0.1;
81  double cycle = std::floor(
82  std::pow(-1.0, (elapsed_time_.toSec() - std::fmod(elapsed_time_.toSec(), time_max.toSec())) /
83  time_max.toSec()));
84  double omega = cycle * omega_max / 2.0 *
85  (1.0 - std::cos(2.0 * M_PI / time_max.toSec() * elapsed_time_.toSec()));
86 
87  for (auto joint_handle : velocity_joint_handles_) {
88  joint_handle.setCommand(omega);
89  }
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
#define M_PI
std::array< std::string, 7 > joint_names
void update(const ros::Time &, const ros::Duration &period) override
#define M_PI_2
std::vector< hardware_interface::JointHandle > velocity_joint_handles_
JointHandle getHandle(const std::string &name)
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(...)
hardware_interface::VelocityJointInterface * velocity_joint_interface_


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