cartesian_pose_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 <memory>
7 #include <string>
8 
12 #include <ros/node_handle.h>
13 #include <ros/time.h>
14 
16 
18 
20  : public controller_interface::MultiInterfaceController<franka_hw::FrankaPoseCartesianInterface,
21  franka_hw::FrankaStateInterface> {
22  public:
23  bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
24  void starting(const ros::Time&) override;
25  void update(const ros::Time&, const ros::Duration& period) override;
26 
27  private:
29  std::unique_ptr<franka_hw::FrankaCartesianPoseHandle> cartesian_pose_handle_;
31  std::array<double, 16> initial_pose_{};
32 };
33 
34 } // namespace franka_example_controllers
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
std::unique_ptr< franka_hw::FrankaCartesianPoseHandle > cartesian_pose_handle_
void update(const ros::Time &, const ros::Duration &period) override


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