Program Listing for File follow_joint_trajectory.h
↰ Return to documentation for file (/tmp/ws/src/robot_controllers/robot_controllers/include/robot_controllers/follow_joint_trajectory.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2020, Michael Ferguson
* Copyright (c) 2014, Fetch Robotics Inc.
* Copyright (c) 2013, Unbounded Robotics Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Unbounded Robotics nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
// Author: Michael Ferguson
#ifndef ROBOT_CONTROLLERS__FOLLOW_JOINT_TRAJECTORY_H_
#define ROBOT_CONTROLLERS__FOLLOW_JOINT_TRAJECTORY_H_
#include <memory>
#include <mutex>
#include <string>
#include <vector>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "robot_controllers_interface/controller.h"
#include "robot_controllers_interface/joint_handle.h"
#include "robot_controllers_interface/controller_manager.h"
#include "control_msgs/action/follow_joint_trajectory.hpp"
#include "angles/angles.h"
#include "robot_controllers/trajectory.h"
#include "robot_controllers/trajectory_spline_sampler.h"
namespace robot_controllers
{
class FollowJointTrajectoryController : public robot_controllers_interface::Controller
{
using FollowJointTrajectoryAction = control_msgs::action::FollowJointTrajectory;
using FollowJointTrajectoryGoal = rclcpp_action::ServerGoalHandle<FollowJointTrajectoryAction>;
public:
FollowJointTrajectoryController();
virtual ~FollowJointTrajectoryController() {}
virtual int init(const std::string& name,
rclcpp::Node::SharedPtr node,
robot_controllers_interface::ControllerManagerPtr manager);
virtual bool start();
virtual bool stop(bool force);
virtual bool reset();
virtual void update(const rclcpp::Time& now, const rclcpp::Duration& dt);
virtual std::string getType()
{
return "robot_controllers/FollowJointTrajectoryController";
}
virtual std::vector<std::string> getCommandedNames();
virtual std::vector<std::string> getClaimedNames();
private:
// rclcpp callbacks for action
rclcpp_action::GoalResponse handle_goal(
const rclcpp_action::GoalUUID & uuid,
std::shared_ptr<const FollowJointTrajectoryAction::Goal> goal_handle);
rclcpp_action::CancelResponse handle_cancel(
const std::shared_ptr<FollowJointTrajectoryGoal> goal_handle);
void handle_accepted(const std::shared_ptr<FollowJointTrajectoryGoal> goal_handle);
void publishCallback();
TrajectoryPoint getPointFromCurrent(bool incl_vel, bool incl_acc, bool zero_vel);
// Handles to node, manager
rclcpp::Node::SharedPtr node_;
robot_controllers_interface::ControllerManagerPtr manager_;
// Parameters
std::vector<std::string> joint_names_;
bool stop_with_action_;
bool stop_on_path_violation_;
// Joint handles
std::vector<robot_controllers_interface::JointHandlePtr> joints_;
std::vector<bool> continuous_;
// Trajectory generation parameters
std::shared_ptr<TrajectorySampler> sampler_;
std::mutex sampler_mutex_;
/*
* In certain cases, we want to start a trajectory at our last sample,
* for instance if we were pre-empted (as is often the case with teleop)
* we need to use the velocity and position of the last sample as a
* starting point.
*/
TrajectoryPoint last_sample_;
// RCLCPP action server interface
rclcpp_action::Server<FollowJointTrajectoryAction>::SharedPtr server_;
std::shared_ptr<FollowJointTrajectoryAction::Feedback> feedback_;
std::shared_ptr<FollowJointTrajectoryGoal> active_goal_;
rclcpp::TimerBase::SharedPtr publish_timer_;
bool has_path_tolerance_;
TrajectoryPoint path_tolerance_;
bool has_goal_tolerance_;
TrajectoryPoint goal_tolerance_;
double goal_time_tolerance_;
rclcpp::Time goal_time_;
};
} // namespace robot_controllers
#endif // ROBOT_CONTROLLERS__FOLLOW_JOINT_TRAJECTORY_H_