SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
nav2z_client
nav2z_client
src
nav2z_client
client_behaviors
cb_pause_slam.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
#include <
nav2z_client/client_behaviors/cb_pause_slam.hpp
>
21
22
namespace
cl_nav2z
23
{
24
CbPauseSlam::CbPauseSlam
(std::string serviceName)
25
:
smacc2
::client_behaviors::
CbServiceCall
<slam_toolbox::srv::Pause>(serviceName.c_str())
26
{
27
}
28
29
void
CbPauseSlam::onEntry
()
30
{
31
this->
requiresComponent
(this->
slam_
);
32
33
auto
currentState
=
slam_
->
getState
();
34
35
if
(
currentState
==
CpSlamToolbox::SlamToolboxState::Resumed
)
36
{
37
RCLCPP_INFO(
38
getLogger
(),
"[CbPauseSlam] calling pause service to toggle from resumed to paused"
);
39
this->
request_
= std::make_shared<slam_toolbox::srv::Pause::Request>();
40
CbServiceCall<slam_toolbox::srv::Pause>::onEntry
();
41
this->
slam_
->
toogleState
();
42
}
43
else
44
{
45
this->
request_
=
nullptr
;
46
RCLCPP_INFO(
47
getLogger
(),
"[CbPauseSlam] calling skipped. The current slam state is already paused."
);
48
}
49
}
50
51
}
// namespace cl_nav2z
cb_pause_slam.hpp
cl_nav2z::CbPauseSlam::slam_
CpSlamToolbox * slam_
Definition
cb_pause_slam.hpp:35
cl_nav2z::CbPauseSlam::CbPauseSlam
CbPauseSlam(std::string serviceName="/slam_toolbox/pause_new_measurements")
Definition
cb_pause_slam.cpp:24
cl_nav2z::CbPauseSlam::onEntry
void onEntry() override
Definition
cb_pause_slam.cpp:29
cl_nav2z::CpSlamToolbox::toogleState
void toogleState()
Definition
cp_slam_toolbox.cpp:28
cl_nav2z::CpSlamToolbox::SlamToolboxState::Resumed
@ Resumed
cl_nav2z::CpSlamToolbox::getState
SlamToolboxState getState()
Definition
cp_slam_toolbox.hpp:43
smacc2::ISmaccClientBehavior::getLogger
virtual rclcpp::Logger getLogger() const
Definition
smacc_client_behavior_base.cpp:43
smacc2::ISmaccClientBehavior::currentState
ISmaccState * currentState
Definition
smacc_client_behavior_base.hpp:81
smacc2::ISmaccClientBehavior::requiresComponent
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
Definition
smacc_client_behavior_impl.hpp:73
smacc2::client_behaviors::CbServiceCall
Definition
cb_call_service.hpp:31
smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause >::request_
std::shared_ptr< typename ServiceType::Request > request_
Definition
cb_call_service.hpp:96
smacc2::client_behaviors::CbServiceCall::onEntry
void onEntry() override
Definition
cb_call_service.hpp:46
cl_nav2z
Definition
backward_global_planner.hpp:28
smacc2
Definition
callback_counter_semaphore.hpp:30
Generated by
1.9.8