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
franka_example_controllers::CartesianVelocityExampleController::elapsed_time_
ros::Duration elapsed_time_
Definition: cartesian_velocity_example_controller.h:29
node_handle.h
franka_example_controllers::CartesianVelocityExampleController::stopping
void stopping(const ros::Time &) override
Definition: cartesian_velocity_example_controller.cpp:92
time.h
franka_example_controllers::CartesianVelocityExampleController::init
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
Definition: cartesian_velocity_example_controller.cpp:18
franka_example_controllers::CartesianVelocityExampleController::starting
void starting(const ros::Time &) override
Definition: cartesian_velocity_example_controller.cpp:72
franka_example_controllers
Definition: cartesian_impedance_example_controller.h:23
franka_hw::FrankaVelocityCartesianInterface
hardware_interface::RobotHW
controller_interface::MultiInterfaceController
franka_example_controllers::CartesianVelocityExampleController::velocity_cartesian_handle_
std::unique_ptr< franka_hw::FrankaCartesianVelocityHandle > velocity_cartesian_handle_
Definition: cartesian_velocity_example_controller.h:28
franka_example_controllers::CartesianVelocityExampleController::velocity_cartesian_interface_
franka_hw::FrankaVelocityCartesianInterface * velocity_cartesian_interface_
Definition: cartesian_velocity_example_controller.h:27
franka_state_interface.h
ros::Time
robot_hw.h
franka_example_controllers::CartesianVelocityExampleController
Definition: cartesian_velocity_example_controller.h:17
ros::Duration
franka_example_controllers::CartesianVelocityExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition: cartesian_velocity_example_controller.cpp:76
franka_cartesian_command_interface.h
ros::NodeHandle
multi_interface_controller.h


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