Main Page
Namespaces
Classes
Files
File List
include
franka_example_controllers
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
9
#include <
controller_interface/multi_interface_controller.h
>
10
#include <
hardware_interface/joint_command_interface.h
>
11
#include <
hardware_interface/robot_hw.h
>
12
#include <
ros/node_handle.h
>
13
#include <
ros/time.h
>
14
15
namespace
franka_example_controllers
{
16
17
class
JointPositionExampleController
:
public
controller_interface::MultiInterfaceController
<
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
:
25
hardware_interface::PositionJointInterface
*
position_joint_interface_
;
26
std::vector<hardware_interface::JointHandle>
position_joint_handles_
;
27
ros::Duration
elapsed_time_
;
28
std::array<double, 7>
initial_pose_
{};
29
};
30
31
}
// namespace franka_example_controllers
ros::NodeHandle
franka_example_controllers::JointPositionExampleController::initial_pose_
std::array< double, 7 > initial_pose_
Definition:
joint_position_example_controller.h:28
multi_interface_controller.h
time.h
ros::Time
franka_example_controllers
Definition:
cartesian_impedance_example_controller.h:22
franka_example_controllers::JointPositionExampleController::position_joint_handles_
std::vector< hardware_interface::JointHandle > position_joint_handles_
Definition:
joint_position_example_controller.h:26
franka_example_controllers::JointPositionExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition:
joint_position_example_controller.cpp:64
franka_example_controllers::JointPositionExampleController::position_joint_interface_
hardware_interface::PositionJointInterface * position_joint_interface_
Definition:
joint_position_example_controller.h:25
robot_hw.h
franka_example_controllers::JointPositionExampleController::init
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
Definition:
joint_position_example_controller.cpp:15
franka_example_controllers::JointPositionExampleController
Definition:
joint_position_example_controller.h:17
node_handle.h
joint_command_interface.h
ros::Duration
franka_example_controllers::JointPositionExampleController::elapsed_time_
ros::Duration elapsed_time_
Definition:
joint_position_example_controller.h:27
franka_example_controllers::JointPositionExampleController::starting
void starting(const ros::Time &) override
Definition:
joint_position_example_controller.cpp:57
controller_interface::MultiInterfaceController
hardware_interface::RobotHW
hardware_interface::PositionJointInterface
franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:17