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
23#include <cl_nav2z/common.hpp>
26
27namespace cl_nav2z
28{
29using namespace smacc2;
30
31CbRotate::CbRotate(float rotate_degree) : rotateDegree(rotate_degree) {}
32
33CbRotate::CbRotate(float rotate_degree, SpinningPlanner spinning_planner)
34: rotateDegree(rotate_degree), spinningPlanner(spinning_planner)
35{
36}
37
39{
40 double angle_increment_degree = rotateDegree;
41
42 CpPlannerSwitcher * plannerSwitcher;
43 this->requiresComponent(plannerSwitcher, ComponentRequirement::HARD);
44
46 {
47 plannerSwitcher->setPureSpinningPlanner();
48 }
49 else
50 {
51 plannerSwitcher->setDefaultPlanners();
52 }
53
54 CpPose * p;
55 this->requiresComponent(p, ComponentRequirement::HARD);
56
57 auto referenceFrame = p->getReferenceFrame();
58 auto currentPoseMsg = p->toPoseMsg();
59
60 tf2::Transform currentPose;
61 tf2::fromMsg(currentPoseMsg, currentPose);
62
63 odom_tracker::CpOdomTracker * odomTracker;
64 this->requiresComponent(odomTracker, ComponentRequirement::SOFT);
65
66 nav2_msgs::action::NavigateToPose::Goal goal;
67 goal.pose.header.frame_id = referenceFrame;
68 //goal.pose.header.stamp = getNode()->now();
69
70 auto currentAngle = tf2::getYaw(currentPoseMsg.orientation);
71 auto targetAngle = currentAngle + angle_increment_degree * M_PI / 180.0;
72 goal.pose.pose.position = currentPoseMsg.position;
73 tf2::Quaternion q;
74 q.setRPY(0, 0, targetAngle);
75 goal.pose.pose.orientation = tf2::toMsg(q);
76
77 geometry_msgs::msg::PoseStamped stampedCurrentPoseMsg;
78 stampedCurrentPoseMsg.header.frame_id = referenceFrame;
79 stampedCurrentPoseMsg.header.stamp = getNode()->now();
80 stampedCurrentPoseMsg.pose = currentPoseMsg;
81
82 auto pathname = this->getCurrentState()->getName() + " - " + getName();
83 odomTracker->pushPath(pathname);
84
85 odomTracker->setStartPoint(stampedCurrentPoseMsg);
87
88 RCLCPP_INFO_STREAM(getLogger(), "current pose: " << currentPoseMsg);
89 RCLCPP_INFO_STREAM(getLogger(), "goal pose: " << goal.pose.pose);
90 this->sendGoal(goal);
91}
92
93} // namespace cl_nav2z
void sendGoal(nav2_msgs::action::NavigateToPose::Goal &goal)
std::optional< cl_nav2z::SpinningPlanner > spinningPlanner
Definition cb_rotate.hpp:35
void onEntry() override
Definition cb_rotate.cpp:38
CbRotate(float rotate_degree)
Definition cb_rotate.cpp:31
void setPureSpinningPlanner(bool commit=true)
void setDefaultPlanners(bool commit=true)
geometry_msgs::msg::Pose toPoseMsg()
Definition cp_pose.hpp:57
const std::string & getReferenceFrame() const
Definition cp_pose.hpp:79
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
virtual std::string getName()=0