SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
nav2z_client
nav2z_client
src
nav2z_client
client_behaviors
cb_rotate_look_at.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_rotate_look_at.hpp
>
22
#include <
nav2z_client/common.hpp
>
23
#include <
nav2z_client/components/goal_checker_switcher/goal_checker_switcher.hpp
>
24
#include <
nav2z_client/components/odom_tracker/odom_tracker.hpp
>
25
#include <
nav2z_client/components/pose/cp_pose.hpp
>
26
#include <
nav2z_client/nav2z_client.hpp
>
27
28
#include <rclcpp/parameter_client.hpp>
29
30
namespace
cl_nav2z
31
{
32
CbRotateLookAt::CbRotateLookAt
() {}
33
34
CbRotateLookAt::CbRotateLookAt
(
const
geometry_msgs::msg::PoseStamped & lookAtPose)
35
: lookAtPose_(lookAtPose)
36
{
37
}
38
39
void
CbRotateLookAt::onEntry
()
40
{
41
cl_nav2z::Pose
* pose;
42
this->
requiresComponent
(pose);
43
44
pose->
waitTransformUpdate
(rclcpp::Rate(20));
45
auto
position = pose->
toPoseMsg
().position;
46
47
if
(
lookAtPose_
)
48
{
49
auto
targetPosition =
lookAtPose_
->pose.position;
50
double
yaw_degrees =
51
atan2(targetPosition.y - position.y, targetPosition.x - position.x) * 180.0 / M_PI;
52
this->
absoluteGoalAngleDegree
= yaw_degrees;
53
}
54
55
CbAbsoluteRotate::onEntry
();
56
}
57
58
}
// namespace cl_nav2z
cb_rotate_look_at.hpp
cl_nav2z::CbAbsoluteRotate::onEntry
void onEntry() override
Definition:
cb_absolute_rotate.cpp:43
cl_nav2z::CbAbsoluteRotate::absoluteGoalAngleDegree
float absoluteGoalAngleDegree
Definition:
cb_absolute_rotate.hpp:34
cl_nav2z::CbRotateLookAt::onEntry
void onEntry() override
Definition:
cb_rotate_look_at.cpp:39
cl_nav2z::CbRotateLookAt::lookAtPose_
std::optional< geometry_msgs::msg::PoseStamped > lookAtPose_
Definition:
cb_rotate_look_at.hpp:35
cl_nav2z::CbRotateLookAt::CbRotateLookAt
CbRotateLookAt()
Definition:
cb_rotate_look_at.cpp:32
cl_nav2z::Pose
Definition:
cp_pose.hpp:44
cl_nav2z::Pose::toPoseMsg
geometry_msgs::msg::Pose toPoseMsg()
Definition:
cp_pose.hpp:57
cl_nav2z::Pose::waitTransformUpdate
void waitTransformUpdate(rclcpp::Rate r=rclcpp::Rate(20))
Definition:
cp_pose.cpp:77
smacc2::ISmaccClientBehavior::requiresComponent
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
Definition:
smacc_client_behavior_impl.hpp:73
common.hpp
cp_pose.hpp
goal_checker_switcher.hpp
cl_nav2z
Definition:
backward_global_planner.hpp:28
nav2z_client.hpp
odom_tracker.hpp
Generated by
1.9.5