src
velocity_smoother_node.cpp
Go to the documentation of this file.
1
/*
2
* Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
18
#include <
ros/ros.h
>
19
#include <boost/thread.hpp>
20
21
#include <
cob_base_velocity_smoother/velocity_smoother.h
>
22
23
using namespace
cob_base_velocity_smoother
;
24
25
std::string
unresolvedName
(
const
std::string &name){
26
size_t
pos = name.find_last_of(
'/'
);
27
return
name.substr(pos + 1);
28
}
29
30
int
main
(
int
argc,
char
** argv)
31
{
32
ros::init
(argc, argv,
"velocity_smoother"
);
33
ros::NodeHandle
nh_p(
"~"
);
34
std::string resolved_name = nh_p.
getUnresolvedNamespace
();
// this always returns like /robosem/goo_arm - why not unresolved?
35
std::string name =
unresolvedName
(resolved_name);
// unresolve it ourselves
36
37
boost::shared_ptr<VelocitySmoother>
vel_smoother_;
38
boost::shared_ptr<boost::thread>
worker_thread_;
39
40
vel_smoother_.reset(
new
VelocitySmoother(name));
41
if
(vel_smoother_->init(nh_p))
42
{
43
ROS_DEBUG_STREAM
(
"Velocity Smoother: initialised ["
<< name <<
"]"
);
44
worker_thread_.reset(
new
boost::thread(&
VelocitySmoother::spin
, vel_smoother_));
45
}
46
else
47
{
48
ROS_ERROR_STREAM
(
"Velocity Smoother: initialisation failed ["
<< name <<
"]"
);
49
}
50
51
ros::Rate
r(100);
52
while
(
ros::ok
())
53
{
54
ros::spinOnce
();
55
r.
sleep
();
56
}
57
58
vel_smoother_->shutdown();
59
worker_thread_->join();
60
61
return
0;
62
}
unresolvedName
std::string unresolvedName(const std::string &name)
Definition:
velocity_smoother_node.cpp:25
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getUnresolvedNamespace
const std::string & getUnresolvedNamespace() const
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::ok
ROSCPP_DECL bool ok()
velocity_smoother.h
ros::Rate::sleep
bool sleep()
cob_base_velocity_smoother::VelocitySmoother::spin
void spin()
Definition:
velocity_smoother.cpp:133
cob_base_velocity_smoother
Definition:
velocity_smoother.h:34
main
int main(int argc, char **argv)
Definition:
velocity_smoother_node.cpp:30
ros::Rate
ros::NodeHandle
cob_base_velocity_smoother
Author(s): Florian Mirus
, Benjamin Maidel
autogenerated on Mon May 1 2023 02:44:18