rrbot_control
src
rrbot_hw_interface.cpp
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2015, University of Colorado, Boulder
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the Univ of CO, Boulder nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
35
/* Author: Dave Coleman
36
Desc: Example ros_control hardware interface blank template for the RRBot
37
For a more detailed simulation example, see sim_hw_interface.cpp
38
*/
39
40
#include <
rrbot_control/rrbot_hw_interface.h
>
41
42
namespace
rrbot_control
43
{
44
RRBotHWInterface::RRBotHWInterface
(
ros::NodeHandle
& nh,
urdf::Model
* urdf_model)
45
:
ros_control_boilerplate
::GenericHWInterface(nh, urdf_model)
46
{
47
ROS_INFO_NAMED
(
"rrbot_hw_interface"
,
"RRBotHWInterface Ready."
);
48
}
49
50
void
RRBotHWInterface::read(
ros::Duration
& elapsed_time)
51
{
52
// ----------------------------------------------------
53
// ----------------------------------------------------
54
// ----------------------------------------------------
55
//
56
// FILL IN YOUR READ COMMAND FROM USB/ETHERNET/ETHERCAT/SERIAL ETC HERE
57
//
58
// ----------------------------------------------------
59
// ----------------------------------------------------
60
// ----------------------------------------------------
61
}
62
63
void
RRBotHWInterface::write(
ros::Duration
& elapsed_time)
64
{
65
// Safety
66
enforceLimits(elapsed_time);
67
68
// ----------------------------------------------------
69
// ----------------------------------------------------
70
// ----------------------------------------------------
71
//
72
// FILL IN YOUR WRITE COMMAND TO USB/ETHERNET/ETHERCAT/SERIAL ETC HERE
73
//
74
// FOR A EASY SIMULATION EXAMPLE, OR FOR CODE TO CALCULATE
75
// VELOCITY FROM POSITION WITH SMOOTHING, SEE
76
// sim_hw_interface.cpp IN THIS PACKAGE
77
//
78
// DUMMY PASS-THROUGH CODE
79
for
(std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
80
joint_position_[joint_id] += joint_position_command_[joint_id];
81
// END DUMMY CODE
82
//
83
// ----------------------------------------------------
84
// ----------------------------------------------------
85
// ----------------------------------------------------
86
}
87
88
void
RRBotHWInterface::enforceLimits(
ros::Duration
& period)
89
{
90
// ----------------------------------------------------
91
// ----------------------------------------------------
92
// ----------------------------------------------------
93
//
94
// CHOOSE THE TYPE OF JOINT LIMITS INTERFACE YOU WANT TO USE
95
// YOU SHOULD ONLY NEED TO USE ONE SATURATION INTERFACE,
96
// DEPENDING ON YOUR CONTROL METHOD
97
//
98
// EXAMPLES:
99
//
100
// Saturation Limits ---------------------------
101
//
102
// Enforces position and velocity
103
pos_jnt_sat_interface_.enforceLimits(period);
104
//
105
// Enforces velocity and acceleration limits
106
// vel_jnt_sat_interface_.enforceLimits(period);
107
//
108
// Enforces position, velocity, and effort
109
// eff_jnt_sat_interface_.enforceLimits(period);
110
111
// Soft limits ---------------------------------
112
//
113
// pos_jnt_soft_limits_.enforceLimits(period);
114
// vel_jnt_soft_limits_.enforceLimits(period);
115
// eff_jnt_soft_limits_.enforceLimits(period);
116
//
117
// ----------------------------------------------------
118
// ----------------------------------------------------
119
// ----------------------------------------------------
120
}
121
122
}
// namespace rrbot_control
rrbot_control::RRBotHWInterface::RRBotHWInterface
RRBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
Definition:
rrbot_hw_interface.cpp:76
ros_control_boilerplate
Definition:
generic_hw_control_loop.h:44
urdf::Model
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
rrbot_control
Definition:
rrbot_hw_interface.h:45
rrbot_hw_interface.h
ros::Duration
ros::NodeHandle
ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Wed Mar 2 2022 00:52:14