Main Page
Related Pages
+
Namespaces
Namespace List
+
Namespace Members
All
Functions
+
Classes
Class List
Class Hierarchy
+
Class Members
+
All
a
c
d
e
f
g
h
i
j
l
m
n
o
p
q
r
s
t
u
v
w
~
+
Functions
a
c
e
f
g
i
j
m
p
r
s
t
u
w
~
+
Variables
a
c
d
e
f
h
i
j
l
m
n
o
p
q
r
s
t
u
v
Typedefs
+
Files
File List
+
File Members
All
Functions
Typedefs
example
srh_example_controller.hpp
Go to the documentation of this file.
1
/*
2
* Copyright 2011 Shadow Robot Company Ltd.
3
*
4
* This program is free software: you can redistribute it and/or modify it
5
* under the terms of the GNU General Public License as published by the Free
6
* Software Foundation version 2 of the License.
7
*
8
* This program is distributed in the hope that it will be useful, but WITHOUT
9
* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11
* more details.
12
*
13
* You should have received a copy of the GNU General Public License along
14
* with this program. If not, see <http://www.gnu.org/licenses/>.
15
*/
16
28
#ifndef _SRH_EXAMPLE_CONTROLLER_HPP_
29
#define _SRH_EXAMPLE_CONTROLLER_HPP_
30
31
#include <
sr_mechanism_controllers/sr_controller.hpp
>
32
#include <string>
33
34
namespace
controller
35
{
36
class
SrhExampleController
:
37
public
SrController
38
{
39
public
:
44
SrhExampleController
();
45
49
virtual
~SrhExampleController
();
50
60
bool
init
(ros_ethercat_model::RobotStateInterface *robot,
ros::NodeHandle
&n);
61
71
bool
init
(ros_ethercat_model::RobotStateInterface *robot,
const
std::string &joint_name);
72
79
virtual
void
starting
(
const
ros::Time
&time);
80
85
virtual
void
update
(
const
ros::Time
&time,
const
ros::Duration
&period);
86
};
87
}
// namespace controller
88
89
/* For the emacs weenies in the crowd.
90
Local Variables:
91
c-basic-offset: 2
92
End:
93
*/
94
95
96
#endif
ros::NodeHandle
controller::SrController
Definition:
sr_controller.hpp:54
ros::Time
controller::SrhExampleController::update
virtual void update(const ros::Time &time, const ros::Duration &period)
Definition:
srh_example_controller.cpp:158
sr_controller.hpp
A generic controller for the Shadow Robot EtherCAT hand's joints.
controller::SrhExampleController::starting
virtual void starting(const ros::Time &time)
Definition:
srh_example_controller.cpp:145
controller::SrhExampleController::init
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
Definition:
srh_example_controller.cpp:53
controller::SrhExampleController::SrhExampleController
SrhExampleController()
Definition:
srh_example_controller.cpp:40
controller::SrhExampleController
Definition:
srh_example_controller.hpp:36
ros::Duration
controller::SrhExampleController::~SrhExampleController
virtual ~SrhExampleController()
Definition:
srh_example_controller.cpp:47
controller
Definition:
srh_example_controller.cpp:37
sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:30