joint_position_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 (position_joint_interface_ == nullptr) {
19  ROS_ERROR(
20  "JointPositionExampleController: Error getting position 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("JointPositionExampleController: Could not parse joint names");
26  }
27  if (joint_names.size() != 7) {
28  ROS_ERROR_STREAM("JointPositionExampleController: Wrong number of joint names, got "
29  << joint_names.size() << " instead of 7 names!");
30  return false;
31  }
32  position_joint_handles_.resize(7);
33  for (size_t i = 0; i < 7; ++i) {
34  try {
38  "JointPositionExampleController: Exception getting joint handles: " << e.what());
39  return false;
40  }
41  }
42 
43  std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
44  for (size_t i = 0; i < q_start.size(); i++) {
45  if (std::abs(position_joint_handles_[i].getPosition() - q_start[i]) > 0.1) {
47  "JointPositionExampleController: Robot is not in the expected starting position for "
48  "running this example. Run `roslaunch franka_example_controllers move_to_start.launch "
49  "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first.");
50  return false;
51  }
52  }
53 
54  return true;
55 }
56 
58  for (size_t i = 0; i < 7; ++i) {
59  initial_pose_[i] = position_joint_handles_[i].getPosition();
60  }
62 }
63 
65  const ros::Duration& period) {
66  elapsed_time_ += period;
67 
68  double delta_angle = M_PI / 16 * (1 - std::cos(M_PI / 5.0 * elapsed_time_.toSec())) * 0.2;
69  for (size_t i = 0; i < 7; ++i) {
70  if (i == 4) {
71  position_joint_handles_[i].setCommand(initial_pose_[i] - delta_angle);
72  } else {
73  position_joint_handles_[i].setCommand(initial_pose_[i] + delta_angle);
74  }
75  }
76 }
77 
78 } // namespace franka_example_controllers
79 
franka_example_controllers::JointPositionExampleController::elapsed_time_
ros::Duration elapsed_time_
Definition: joint_position_example_controller.h:27
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
HardwareResourceManager< JointHandle, ClaimResources >::getHandle
JointHandle getHandle(const std::string &name)
hardware_interface::HardwareInterfaceException::what
const char * what() const noexcept override
hardware_interface::InterfaceManager::get
T * get()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
franka_example_controllers::JointPositionExampleController::initial_pose_
std::array< double, 7 > initial_pose_
Definition: joint_position_example_controller.h:28
franka_example_controllers::JointPositionExampleController
Definition: joint_position_example_controller.h:17
hardware_interface.h
joint_position_example_controller.h
class_list_macros.h
controller_interface::ControllerBase
franka_example_controllers
Definition: cartesian_impedance_example_controller.h:23
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
franka_example_controllers::JointPositionExampleController::starting
void starting(const ros::Time &) override
Definition: joint_position_example_controller.cpp:57
joint_command_interface.h
hardware_interface::RobotHW
controller_base.h
ROS_ERROR
#define ROS_ERROR(...)
franka_example_controllers::JointPositionExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition: joint_position_example_controller.cpp:64
hardware_interface::HardwareInterfaceException
ros::Time
joint_names
std::array< std::string, 7 > joint_names
franka_example_controllers::JointPositionExampleController::position_joint_interface_
hardware_interface::PositionJointInterface * position_joint_interface_
Definition: joint_position_example_controller.h:25
DurationBase< Duration >::toSec
double toSec() const
hardware_interface::PositionJointInterface
franka_example_controllers::JointPositionExampleController::init
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
Definition: joint_position_example_controller.cpp:15
ros::Duration
ros::NodeHandle
franka_example_controllers::JointPositionExampleController::position_joint_handles_
std::vector< hardware_interface::JointHandle > position_joint_handles_
Definition: joint_position_example_controller.h:26


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:26