SMACC2
smacc2_client_library
nav2z_client
nav2z_client
src
nav2z_client
client_behaviors
cb_wait_pose.cpp
Go to the documentation of this file.
1
// Copyright 2021 RobosoftAI Inc.
2
//
3
// Licensed under the Apache License, Version 2.0 (the "License");
4
// you may not use this file except in compliance with the License.
5
// You may obtain a copy of the License at
6
//
7
// http://www.apache.org/licenses/LICENSE-2.0
8
//
9
// Unless required by applicable law or agreed to in writing, software
10
// distributed under the License is distributed on an "AS IS" BASIS,
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
// See the License for the specific language governing permissions and
13
// limitations under the License.
14
15
/*****************************************************************************************************************
16
*
17
* Authors: Pablo Inigo Blasco, Brett Aldrich
18
*
19
******************************************************************************************************************/
20
21
#include <
nav2z_client/client_behaviors/cb_wait_pose.hpp
>
22
#include <
nav2z_client/components/pose/cp_pose.hpp
>
23
24
#include <
nav2z_client/common.hpp
>
25
#include <rclcpp/parameter_client.hpp>
26
27
namespace
cl_nav2z
28
{
29
CbWaitPose::CbWaitPose
() {}
30
31
CbWaitPose::~CbWaitPose
() {}
32
33
void
CbWaitPose::onEntry
()
34
{
35
auto
pose = this->
moveBaseClient_
->
getComponent
<
Pose
>();
36
try
37
{
38
pose->
waitTransformUpdate
(rclcpp::Rate(20));
39
auto
posemsg = pose->toPoseMsg();
40
RCLCPP_INFO_STREAM(
getLogger
(),
"[CbWaitPose] pose arrived: "
<< std::endl << posemsg);
41
}
42
catch
(std::exception & ex)
43
{
44
RCLCPP_INFO(
getLogger
(),
"[CbWaitPose] error getting the robot pose"
);
45
this->
postFailureEvent
();
46
return
;
47
}
48
49
RCLCPP_INFO(
getLogger
(),
"[CbWaitPose] pose received"
);
50
this->
postSuccessEvent
();
51
}
52
}
// namespace cl_nav2z
cb_wait_pose.hpp
cl_nav2z::CbWaitPose::CbWaitPose
CbWaitPose()
Definition:
cb_wait_pose.cpp:29
cl_nav2z::CbWaitPose::moveBaseClient_
cl_nav2z::ClNav2Z * moveBaseClient_
Definition:
cb_wait_pose.hpp:57
cl_nav2z::CbWaitPose::~CbWaitPose
virtual ~CbWaitPose()
Definition:
cb_wait_pose.cpp:31
cl_nav2z::CbWaitPose::onEntry
void onEntry() override
Definition:
cb_wait_pose.cpp:33
cl_nav2z::Pose
Definition:
cp_pose.hpp:45
cl_nav2z::Pose::waitTransformUpdate
void waitTransformUpdate(rclcpp::Rate r=rclcpp::Rate(20))
Definition:
cp_pose.cpp:77
smacc2::ISmaccClientBehavior::getLogger
virtual rclcpp::Logger getLogger()
Definition:
smacc_client_behavior_base.cpp:40
smacc2::ISmaccClient::getComponent
TComponent * getComponent()
Definition:
smacc_client_impl.hpp:41
smacc2::SmaccAsyncClientBehavior::postSuccessEvent
void postSuccessEvent()
Definition:
smacc_client_async_behavior.cpp:114
smacc2::SmaccAsyncClientBehavior::postFailureEvent
void postFailureEvent()
Definition:
smacc_client_async_behavior.cpp:116
common.hpp
cp_pose.hpp
cl_nav2z
Definition:
backward_global_planner.hpp:28
Generated by
1.9.4