cartesian_velocity_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 <memory>
6 #include <string>
7 
12 #include <ros/node_handle.h>
13 #include <ros/time.h>
14 
16 
18  franka_hw::FrankaVelocityCartesianInterface,
19  franka_hw::FrankaStateInterface> {
20  public:
21  bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
22  void update(const ros::Time&, const ros::Duration& period) override;
23  void starting(const ros::Time&) override;
24  void stopping(const ros::Time&) override;
25 
26  private:
28  std::unique_ptr<franka_hw::FrankaCartesianVelocityHandle> velocity_cartesian_handle_;
30 };
31 
32 } // namespace franka_example_controllers
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
std::unique_ptr< franka_hw::FrankaCartesianVelocityHandle > velocity_cartesian_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