model_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
3 
5 
6 #include <algorithm>
7 #include <array>
8 #include <cstring>
9 #include <iterator>
10 #include <memory>
11 
15 #include <ros/ros.h>
16 
19 
20 namespace {
21 template <class T, size_t N>
22 std::ostream& operator<<(std::ostream& ostream, const std::array<T, N>& array) {
23  ostream << "[";
24  std::copy(array.cbegin(), array.cend() - 1, std::ostream_iterator<T>(ostream, ","));
25  std::copy(array.cend() - 1, array.cend(), std::ostream_iterator<T>(ostream));
26  ostream << "]";
27  return ostream;
28 }
29 } // anonymous namespace
30 
32 
34  ros::NodeHandle& node_handle) {
36  if (franka_state_interface_ == nullptr) {
37  ROS_ERROR("ModelExampleController: Could not get Franka state interface from hardware");
38  return false;
39  }
40  std::string arm_id;
41  if (!node_handle.getParam("arm_id", arm_id)) {
42  ROS_ERROR("ModelExampleController: Could not read parameter arm_id");
43  return false;
44  }
46  if (model_interface_ == nullptr) {
47  ROS_ERROR_STREAM("ModelExampleController: Error getting model interface from hardware");
48  return false;
49  }
50 
51  try {
52  franka_state_handle_ = std::make_unique<franka_hw::FrankaStateHandle>(
53  franka_state_interface_->getHandle(arm_id + "_robot"));
56  "ModelExampleController: Exception getting franka state handle: " << ex.what());
57  return false;
58  }
59 
60  try {
61  model_handle_ = std::make_unique<franka_hw::FrankaModelHandle>(
62  model_interface_->getHandle(arm_id + "_model"));
65  "ModelExampleController: Exception getting model handle from interface: " << ex.what());
66  return false;
67  }
68  return true;
69 }
70 
71 void ModelExampleController::update(const ros::Time& /*time*/, const ros::Duration& /*period*/) {
72  if (rate_trigger_()) {
73  std::array<double, 49> mass = model_handle_->getMass();
74  std::array<double, 7> coriolis = model_handle_->getCoriolis();
75  std::array<double, 7> gravity = model_handle_->getGravity();
76  std::array<double, 16> pose = model_handle_->getPose(franka::Frame::kJoint4);
77  std::array<double, 42> joint4_body_jacobian =
78  model_handle_->getBodyJacobian(franka::Frame::kJoint4);
79  std::array<double, 42> endeffector_zero_jacobian =
80  model_handle_->getZeroJacobian(franka::Frame::kEndEffector);
81 
82  ROS_INFO("--------------------------------------------------");
83  ROS_INFO_STREAM("mass :" << mass);
84  ROS_INFO_STREAM("coriolis: " << coriolis);
85  ROS_INFO_STREAM("gravity :" << gravity);
86  ROS_INFO_STREAM("joint_pose :" << pose);
87  ROS_INFO_STREAM("joint4_body_jacobian :" << joint4_body_jacobian);
88  ROS_INFO_STREAM("joint_zero_jacobian :" << endeffector_zero_jacobian);
89  }
90 }
91 
92 } // namespace franka_example_controllers
93 
model_example_controller.h
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
franka_example_controllers::ModelExampleController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Definition: model_example_controller.cpp:33
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
dual_arm_interactive_marker.pose
pose
Definition: dual_arm_interactive_marker.py:154
franka_example_controllers::ModelExampleController::rate_trigger_
franka_hw::TriggerRate rate_trigger_
Definition: model_example_controller.h:31
franka_example_controllers::ModelExampleController::model_interface_
franka_hw::FrankaModelInterface * model_interface_
Definition: model_example_controller.h:29
hardware_interface.h
franka_example_controllers::ModelExampleController::update
void update(const ros::Time &, const ros::Duration &) override
Definition: model_example_controller.cpp:71
franka_example_controllers::ModelExampleController::franka_state_handle_
std::unique_ptr< franka_hw::FrankaStateHandle > franka_state_handle_
Definition: model_example_controller.h:28
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)
hardware_interface::RobotHW
controller_base.h
arm_id
std::string arm_id
operator<<
std::ostream & operator<<(std::ostream &ostream, ControlMode mode)
ROS_ERROR
#define ROS_ERROR(...)
franka_hw::FrankaStateInterface
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
franka_example_controllers::ModelExampleController
Definition: model_example_controller.h:19
franka_state_interface.h
franka_hw::FrankaModelInterface
hardware_interface::HardwareInterfaceException
ros::Time
franka_model_interface.h
franka_example_controllers::ModelExampleController::model_handle_
std::unique_ptr< franka_hw::FrankaModelHandle > model_handle_
Definition: model_example_controller.h:30
ROS_INFO
#define ROS_INFO(...)
ros::Duration
franka_example_controllers::ModelExampleController::franka_state_interface_
franka_hw::FrankaStateInterface * franka_state_interface_
Definition: model_example_controller.h:27
ros::NodeHandle


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