Program Listing for File spin.hpp
↰ Return to documentation for file (include/nav2_behaviors/plugins/spin.hpp
)
// Copyright (c) 2018 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
#define NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_
#include <chrono>
#include <string>
#include <memory>
#include "nav2_behaviors/timed_behavior.hpp"
#include "nav2_msgs/action/spin.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
namespace nav2_behaviors
{
using SpinAction = nav2_msgs::action::Spin;
class Spin : public TimedBehavior<SpinAction>
{
using CostmapInfoType = nav2_core::CostmapInfoType;
public:
using SpinActionGoal = SpinAction::Goal;
using SpinActionResult = SpinAction::Result;
Spin();
~Spin();
ResultStatus onRun(const std::shared_ptr<const SpinActionGoal> command) override;
void onConfigure() override;
ResultStatus onCycleUpdate() override;
CostmapInfoType getResourceInfo() override {return CostmapInfoType::LOCAL;}
protected:
bool isCollisionFree(
const double & distance,
const geometry_msgs::msg::Twist & cmd_vel,
geometry_msgs::msg::Pose2D & pose2d);
SpinAction::Feedback::SharedPtr feedback_;
double min_rotational_vel_;
double max_rotational_vel_;
double rotational_acc_lim_;
double cmd_yaw_;
double prev_yaw_;
double relative_yaw_;
double simulate_ahead_time_;
rclcpp::Duration command_time_allowance_{0, 0};
rclcpp::Time end_time_;
};
} // namespace nav2_behaviors
#endif // NAV2_BEHAVIORS__PLUGINS__SPIN_HPP_