test
simple_bot_hw.cpp
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2020, Franco Fusco.
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 Willow Garage 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
36
#include <chrono>
37
#include <cmath>
38
#include <thread>
39
40
// ROS
41
#include <
ros/ros.h
>
42
#include <rosgraph_msgs/Clock.h>
43
#include <std_msgs/Float64.h>
44
45
// ros_control
46
#include <controller_manager/controller_manager.h>
47
#include <
hardware_interface/joint_command_interface.h
>
48
#include <
hardware_interface/joint_state_interface.h
>
49
#include <
hardware_interface/robot_hw.h
>
50
#include <
realtime_tools/realtime_buffer.h
>
51
52
class
SimpleBot
:
public
hardware_interface::RobotHW
53
{
54
public
:
55
static
constexpr
double
period
= 0.01;
56
57
SimpleBot
()
58
:
pos_
(0.0)
59
,
vel_
(0.0)
60
,
eff_
(0.0)
61
,
max_eff_
(10.0)
62
,
cmd_
(0.0)
63
{
64
// joint state interface
65
hardware_interface::JointStateHandle
state_handle(
"joint"
, &
pos_
, &
vel_
, &
eff_
);
66
state_interface_
.
registerHandle
(state_handle);
67
registerInterface
(&
state_interface_
);
68
// effort interface
69
hardware_interface::JointHandle
effort_handle(
state_interface_
.
getHandle
(
"joint"
), &
cmd_
);
70
effort_interface_
.
registerHandle
(effort_handle);
71
registerInterface
(&
effort_interface_
);
72
}
73
74
void
read
() {
75
// update current state
76
pos_
+=
period
*
vel_
+ 0.5*std::pow(
period
, 2.0) *
eff_
;
77
vel_
+=
period
*
eff_
;
78
}
79
80
void
write
() {
81
// store current command
82
eff_
=
cmd_
;
83
if
(std::fabs(
eff_
) >
max_eff_
) {
84
ROS_WARN
(
"Large effort command received: %f; cutting down to % f"
,
eff_
,
max_eff_
);
85
eff_
=
eff_
> 0.0 ?
max_eff_
: -
max_eff_
;
86
}
87
}
88
89
private
:
90
hardware_interface::JointStateInterface
state_interface_
;
91
hardware_interface::EffortJointInterface
effort_interface_
;
92
double
cmd_
,
pos_
,
vel_
,
eff_
;
93
double
max_eff_
;
94
};
95
96
97
int
main
(
int
argc,
char
**argv)
98
{
99
ros::init
(argc, argv,
"simple_bot_hw"
);
100
ros::NodeHandle
nh;
101
SimpleBot
bot;
102
ros::Publisher
clock_publisher = nh.
advertise
<rosgraph_msgs::Clock>(
"/clock"
, 1);
103
nh.
setParam
(
"/use_sim_time"
,
true
);
104
controller_manager::ControllerManager cm(&bot, nh);
105
ros::AsyncSpinner
spinner
(2);
106
spinner
.start();
107
108
ros::Rate
rate(1.0/bot.
period
);
109
ros::Duration
period(bot.
period
);
110
double
sim_time = 0.0;
111
112
// main "simulation"
113
while
(
ros::ok
()) {
114
auto
begin = std::chrono::system_clock::now();
115
bot.
read
();
116
cm.update(
ros::Time
(sim_time), period);
117
bot.
write
();
118
auto
end = std::chrono::system_clock::now();
119
double
elapsed = std::chrono::duration_cast<std::chrono::duration<double> >((end - begin)).count();
120
if
(bot.
period
> elapsed)
121
std::this_thread::sleep_for(std::chrono::duration<double>(bot.
period
- elapsed));
122
rosgraph_msgs::Clock clock;
123
clock.clock =
ros::Time
(sim_time);
124
clock_publisher.
publish
(clock);
125
sim_time += bot.
period
;
126
}
127
128
spinner
.stop();
129
130
return
0;
131
}
SimpleBot::max_eff_
double max_eff_
Definition:
simple_bot_hw.cpp:125
main
int main(int argc, char **argv)
Definition:
simple_bot_hw.cpp:97
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
ros::Publisher
SimpleBot::read
void read()
Definition:
simple_bot_hw.cpp:106
SimpleBot::state_interface_
hardware_interface::JointStateInterface state_interface_
Definition:
simple_bot_hw.cpp:122
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
HardwareResourceManager< JointStateHandle >::getHandle
JointStateHandle getHandle(const std::string &name)
hardware_interface::JointStateInterface
SimpleBot::period
static constexpr double period
Definition:
simple_bot_hw.cpp:87
ros.h
realtime_buffer.h
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
ros::AsyncSpinner
SimpleBot
Definition:
simple_bot_hw.cpp:52
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
spinner
void spinner()
joint_command_interface.h
hardware_interface::RobotHW
SimpleBot::vel_
double vel_
Definition:
simple_bot_hw.cpp:124
hardware_interface::JointStateHandle
hardware_interface::EffortJointInterface
ROS_WARN
#define ROS_WARN(...)
ResourceManager< JointStateHandle >::registerHandle
void registerHandle(const JointStateHandle &handle)
joint_state_interface.h
hardware_interface::JointHandle
SimpleBot::SimpleBot
SimpleBot()
Definition:
simple_bot_hw.cpp:89
ros::Time
SimpleBot::pos_
double pos_
Definition:
simple_bot_hw.cpp:124
robot_hw.h
ros::Rate
SimpleBot::cmd_
double cmd_
Definition:
simple_bot_hw.cpp:124
SimpleBot::write
void write()
Definition:
simple_bot_hw.cpp:112
SimpleBot::effort_interface_
hardware_interface::EffortJointInterface effort_interface_
Definition:
simple_bot_hw.cpp:123
SimpleBot::eff_
double eff_
Definition:
simple_bot_hw.cpp:124
ros::Duration
ros::NodeHandle
effort_controllers
Author(s): Vijay Pradeep
autogenerated on Fri May 24 2024 02:41:22