SMACC2
smacc2_sm_reference_library
sm_autoware_avp
src
sm_autoware_avp
clients
autoware_client
client_behaviors
cb_setup_initial_pose_estimation.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 "
sm_autoware_avp/clients/autoware_client/client_behaviors/cb_setup_initial_pose_estimation.hpp
"
22
#include "
sm_autoware_avp/clients/autoware_client/cl_autoware.hpp
"
23
24
namespace
sm_autoware_avp
25
{
26
namespace
clients
27
{
28
namespace
autoware_client
29
{
30
CbSetupInitialPoseEstimation::CbSetupInitialPoseEstimation
(
31
const
geometry_msgs::msg::PoseWithCovarianceStamped & initialStatePose)
32
: initialStatePose_(initialStatePose)
33
{
34
}
35
36
void
CbSetupInitialPoseEstimation::onEntry
()
37
{
38
sm_autoware_avp::clients::ClAutoware
* autowareClient_;
39
initialStatePose_
.header.stamp =
getNode
()->now();
40
initialStatePose_
.header.frame_id =
"map"
;
41
42
this->
requiresClient
(autowareClient_);
43
44
autowareClient_->
publishInitialPoseEstimation
(
initialStatePose_
);
45
}
46
47
void
CbSetupInitialPoseEstimation::onExit
() {}
48
49
}
// namespace autoware_client
50
}
// namespace clients
51
}
// namespace sm_autoware_avp
cb_setup_initial_pose_estimation.hpp
cl_autoware.hpp
sm_autoware_avp::clients::ClAutoware
Definition:
cl_autoware.hpp:50
sm_autoware_avp::clients::ClAutoware::publishInitialPoseEstimation
void publishInitialPoseEstimation(const geometry_msgs::msg::PoseWithCovarianceStamped &msg)
Definition:
cl_autoware.hpp:152
sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::CbSetupInitialPoseEstimation
CbSetupInitialPoseEstimation(const geometry_msgs::msg::PoseWithCovarianceStamped &initialStatePose)
Definition:
cb_setup_initial_pose_estimation.cpp:30
sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::onEntry
virtual void onEntry() override
Definition:
cb_setup_initial_pose_estimation.cpp:36
sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::initialStatePose_
geometry_msgs::msg::PoseWithCovarianceStamped initialStatePose_
Definition:
cb_setup_initial_pose_estimation.hpp:41
sm_autoware_avp::clients::autoware_client::CbSetupInitialPoseEstimation::onExit
void onExit() override
Definition:
cb_setup_initial_pose_estimation.cpp:47
smacc2::ISmaccClientBehavior::getNode
virtual rclcpp::Node::SharedPtr getNode()
Definition:
smacc_client_behavior_base.cpp:38
smacc2::ISmaccClientBehavior::requiresClient
void requiresClient(SmaccClientType *&storage)
Definition:
smacc_client_behavior_impl.hpp:67
sm_autoware_avp
Definition:
cl_autoware.hpp:33
Generated by
1.9.4