SMACC2
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
23
24namespace sm_autoware_avp
25{
26namespace clients
27{
28namespace autoware_client
29{
31 const geometry_msgs::msg::PoseWithCovarianceStamped & initialStatePose)
32: initialStatePose_(initialStatePose)
33{
34}
35
37{
39 initialStatePose_.header.stamp = getNode()->now();
40 initialStatePose_.header.frame_id = "map";
41
42 this->requiresClient(autowareClient_);
43
45}
46
48
49} // namespace autoware_client
50} // namespace clients
51} // namespace sm_autoware_avp
void publishInitialPoseEstimation(const geometry_msgs::msg::PoseWithCovarianceStamped &msg)
CbSetupInitialPoseEstimation(const geometry_msgs::msg::PoseWithCovarianceStamped &initialStatePose)
virtual rclcpp::Node::SharedPtr getNode()
void requiresClient(SmaccClientType *&storage)