include
pr2_mechanism_controllers
caster_controller.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2008, Willow Garage, Inc.
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the Willow Garage, Inc. nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*/
29
30
/*
31
* Author: Stuart Glaser
32
33
Example config:
34
35
<controller type="CasterController" name="a_caster">
36
<joints caster="caster_joint" wheel_l="wheel_left_joint" wheel_r="wheel_right_joint">
37
<caster_pid p="5.0" i="0.0" d="0.0" iClamp="0.0" />
38
<wheel_pid p="4.0" i="0.0" d="0.0" iClamp="0.0" />
39
</controller>
40
41
YAML config
42
\verbatim
43
caster_fl:
44
type: CasterController
45
caster_pid: {p: 6.0}
46
wheel_pid: {p: 4.0}
47
joints:
48
caster: fl_caster_rotation_joint
49
wheel_l: fl_caster_l_wheel_joint
50
wheel_r: fl_caster_r_wheel_joint
51
\endverbatim
52
53
*/
54
55
#ifndef CASTER_CONTROLLER_H
56
#define CASTER_CONTROLLER_H
57
58
#include "
ros/node_handle.h
"
59
60
#include "
pr2_controller_interface/controller.h
"
61
#include "
pr2_mechanism_model/robot.h
"
62
#include "
control_toolbox/pid.h
"
63
#include "
robot_mechanism_controllers/joint_velocity_controller.h
"
64
#include "std_msgs/Float64.h"
65
#include <boost/thread/condition.hpp>
66
67
namespace
controller
{
68
69
class
CasterController
:
public
pr2_controller_interface::Controller
70
{
71
public
:
72
const
static
double
WHEEL_RADIUS
;
73
const
static
double
WHEEL_OFFSET
;
74
75
CasterController
();
76
~CasterController
();
77
78
bool
init
(
pr2_mechanism_model::RobotState
*robot_state,
79
const
std::string &caster_joint,
80
const
std::string &wheel_l_joint,
const
std::string &wheel_r_joint,
81
const
control_toolbox::Pid
&caster_pid,
const
control_toolbox::Pid
&wheel_pid);
82
bool
init
(
pr2_mechanism_model::RobotState
*robot,
ros::NodeHandle
&n);
83
84
void
update
();
85
86
double
steer_velocity_
;
87
double
drive_velocity_
;
88
89
double
getSteerPosition
() {
return
caster_
->
position_
; }
90
double
getSteerVelocity
() {
return
caster_
->
velocity_
; }
91
92
pr2_mechanism_model::JointState
*
caster_
;
93
94
private
:
95
ros::NodeHandle
node_
;
96
JointVelocityController
caster_vel_
,
wheel_l_vel_
,
wheel_r_vel_
;
97
ros::Subscriber
steer_cmd_
;
98
ros::Subscriber
drive_cmd_
;
99
100
void
setSteerCB
(
const
std_msgs::Float64ConstPtr& msg);
101
void
setDriveCB
(
const
std_msgs::Float64ConstPtr& msg);
102
};
103
104
}
105
106
#endif
controller::CasterController::setSteerCB
void setSteerCB(const std_msgs::Float64ConstPtr &msg)
Definition:
caster_controller.cpp:154
node_handle.h
pr2_mechanism_model::JointState
controller::CasterController::CasterController
CasterController()
Definition:
caster_controller.cpp:44
controller::CasterController::steer_velocity_
double steer_velocity_
Definition:
caster_controller.h:86
controller::CasterController::caster_vel_
JointVelocityController caster_vel_
Definition:
caster_controller.h:96
pr2_mechanism_model::JointState::velocity_
double velocity_
joint_velocity_controller.h
controller::CasterController::getSteerVelocity
double getSteerVelocity()
Definition:
caster_controller.h:90
controller::CasterController::getSteerPosition
double getSteerPosition()
Definition:
caster_controller.h:89
pr2_mechanism_model::JointState::position_
double position_
controller::CasterController::WHEEL_OFFSET
const static double WHEEL_OFFSET
Definition:
caster_controller.h:73
controller::CasterController::drive_cmd_
ros::Subscriber drive_cmd_
Definition:
caster_controller.h:98
controller::CasterController::node_
ros::NodeHandle node_
Definition:
caster_controller.h:95
controller.h
controller
pr2_mechanism_model::RobotState
pr2_controller_interface::Controller
controller::CasterController::steer_cmd_
ros::Subscriber steer_cmd_
Definition:
caster_controller.h:97
controller::JointVelocityController
controller::CasterController::~CasterController
~CasterController()
Definition:
caster_controller.cpp:49
controller::CasterController::setDriveCB
void setDriveCB(const std_msgs::Float64ConstPtr &msg)
Definition:
caster_controller.cpp:159
controller::CasterController::caster_
pr2_mechanism_model::JointState * caster_
Definition:
caster_controller.h:92
controller::CasterController::drive_velocity_
double drive_velocity_
Definition:
caster_controller.h:87
control_toolbox::Pid
controller::CasterController::init
bool init(pr2_mechanism_model::RobotState *robot_state, const std::string &caster_joint, const std::string &wheel_l_joint, const std::string &wheel_r_joint, const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid)
Definition:
caster_controller.cpp:53
controller::CasterController::wheel_l_vel_
JointVelocityController wheel_l_vel_
Definition:
caster_controller.h:96
pid.h
controller::CasterController::WHEEL_RADIUS
const static double WHEEL_RADIUS
Definition:
caster_controller.h:72
controller::CasterController
Definition:
caster_controller.h:69
controller::CasterController::wheel_r_vel_
JointVelocityController wheel_r_vel_
Definition:
caster_controller.h:96
ros::NodeHandle
ros::Subscriber
robot.h
controller::CasterController::update
void update()
Definition:
caster_controller.cpp:140
pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Sat Nov 12 2022 03:33:25