joint_position_example_controller.h
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 #pragma once
4 
5 #include <array>
6 #include <string>
7 #include <vector>
8 
12 #include <ros/node_handle.h>
13 #include <ros/time.h>
14 
16 
18  hardware_interface::PositionJointInterface> {
19  public:
20  bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
21  void starting(const ros::Time&) override;
22  void update(const ros::Time&, const ros::Duration& period) override;
23 
24  private:
26  std::vector<hardware_interface::JointHandle> position_joint_handles_;
28  std::array<double, 7> initial_pose_{};
29 };
30 
31 } // namespace franka_example_controllers
std::vector< hardware_interface::JointHandle > position_joint_handles_
void update(const ros::Time &, const ros::Duration &period) override
hardware_interface::PositionJointInterface * position_joint_interface_
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override


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