SMACC
Loading...
Searching...
No Matches
cb_circular_pivot_motion.h
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018-2020
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6#pragma once
7
9#include "tf/transform_datatypes.h"
10#include <tf/transform_listener.h>
11
13{
15 {
16 public:
17 boost::optional<double> angularSpeed_rad_s_;
18 boost::optional<double> linearSpeed_m_s_;
19
20 // if not specified it would be used the current robot pose
21 boost::optional<geometry_msgs::Pose> relativeInitialPose_;
22
23 CbCircularPivotMotion(std::string tipLink = "");
24
25 CbCircularPivotMotion(const geometry_msgs::PoseStamped &planePivotPose, double deltaRadians, std::string tipLink = "");
26
27 CbCircularPivotMotion(const geometry_msgs::PoseStamped &planePivotPose, const geometry_msgs::Pose &relativeInitialPose, double deltaRadians, std::string tipLink = "");
28
29 virtual void generateTrajectory() override;
30
31 virtual void createMarkers() override;
32
33 protected:
34 geometry_msgs::PoseStamped planePivotPose_;
35
37
38 private:
40 };
41
42} // namespace cl_move_group_interface
boost::optional< geometry_msgs::Pose > relativeInitialPose_