SMACC2
Loading...
Searching...
No Matches
cb_rotate.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 <geometry_msgs/msg/quaternion_stamped.hpp>
21
26
27namespace cl_nav2z
28{
29CbRotate::CbRotate(float rotate_degree) : rotateDegree(rotate_degree) {}
30
31CbRotate::CbRotate(float rotate_degree, SpinningPlanner spinning_planner)
32: rotateDegree(rotate_degree), spinningPlanner(spinning_planner)
33{
34}
35
37{
38 double angle_increment_degree = rotateDegree;
39
40 auto plannerSwitcher = nav2zClient_->getComponent<PlannerSwitcher>();
41
43 {
44 plannerSwitcher->setPureSpinningPlanner();
45 }
46 else
47 {
48 plannerSwitcher->setDefaultPlanners();
49 }
50
52 auto referenceFrame = p->getReferenceFrame();
53 auto currentPoseMsg = p->toPoseMsg();
54
55 tf2::Transform currentPose;
56 tf2::fromMsg(currentPoseMsg, currentPose);
57
59 ClNav2Z::Goal goal;
60 goal.pose.header.frame_id = referenceFrame;
61 //goal.pose.header.stamp = getNode()->now();
62
63 auto currentAngle = tf2::getYaw(currentPoseMsg.orientation);
64 auto targetAngle = currentAngle + angle_increment_degree * M_PI / 180.0;
65 goal.pose.pose.position = currentPoseMsg.position;
66 tf2::Quaternion q;
67 q.setRPY(0, 0, targetAngle);
68 goal.pose.pose.orientation = tf2::toMsg(q);
69
70 geometry_msgs::msg::PoseStamped stampedCurrentPoseMsg;
71 stampedCurrentPoseMsg.header.frame_id = referenceFrame;
72 stampedCurrentPoseMsg.header.stamp = getNode()->now();
73 stampedCurrentPoseMsg.pose = currentPoseMsg;
74
76 auto pathname = this->getCurrentState()->getName() + " - " + getName();
77 odomTracker->pushPath(pathname);
78
79 odomTracker->setStartPoint(stampedCurrentPoseMsg);
80 odomTracker->setWorkingMode(odom_tracker::WorkingMode::RECORD_PATH);
81
82 RCLCPP_INFO_STREAM(getLogger(), "current pose: " << currentPoseMsg);
83 RCLCPP_INFO_STREAM(getLogger(), "goal pose: " << goal.pose.pose);
84 this->sendGoal(goal);
85}
86
87} // namespace cl_nav2z
std::optional< cl_nav2z::SpinningPlanner > spinningPlanner
Definition: cb_rotate.hpp:35
void onEntry() override
Definition: cb_rotate.cpp:36
CbRotate(float rotate_degree)
Definition: cb_rotate.cpp:29
void setPureSpinningPlanner(bool commit=true)
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:76
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)
TComponent * getComponent()
virtual std::string getName()=0