SMACC2
Loading...
Searching...
No Matches
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
23
24#include <cl_nav2z/common.hpp>
25#include <rclcpp/parameter_client.hpp>
26
27namespace cl_nav2z
28{
29using namespace smacc2;
30
32
34
36{
37 cl_nav2z::CpPose * pose = nullptr;
38 this->requiresComponent(pose, ComponentRequirement::SOFT);
39 try
40 {
41 pose->waitTransformUpdate(rclcpp::Rate(20));
42 auto posemsg = pose->toPoseMsg();
43 RCLCPP_INFO_STREAM(getLogger(), "[CbWaitPose] pose arrived: " << std::endl << posemsg);
44 }
45 catch (std::exception & ex)
46 {
47 RCLCPP_INFO(getLogger(), "[CbWaitPose] error getting the robot pose");
48 this->postFailureEvent();
49 return;
50 }
51
52 RCLCPP_INFO(getLogger(), "[CbWaitPose] pose received");
53 this->postSuccessEvent();
54}
55} // namespace cl_nav2z
void onEntry() override
geometry_msgs::msg::Pose toPoseMsg()
Definition cp_pose.hpp:57
void waitTransformUpdate(rclcpp::Rate r=rclcpp::Rate(20))
Definition cp_pose.cpp:77
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)