SMACC
Loading...
Searching...
No Matches
smacc_client_library
move_group_interface_client
include
move_group_interface_client
client_behaviors
cb_pouring_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
8
#include "
cb_move_end_effector_trajectory.h
"
9
#include "tf/transform_datatypes.h"
10
#include <tf/transform_listener.h>
11
12
namespace
cl_move_group_interface
13
{
14
class
CbCircularPouringMotion
:
public
CbMoveEndEffectorTrajectory
15
{
16
public
:
17
boost::optional<double>
angularSpeed_rad_s_
;
18
19
boost::optional<double>
linearSpeed_m_s_
;
20
21
CbCircularPouringMotion
(
const
geometry_msgs::Point &pivotPoint,
double
deltaHeight, std::string tipLink , std::string globalFrame);
22
23
virtual
void
generateTrajectory
()
override
;
24
25
virtual
void
createMarkers
()
override
;
26
27
geometry_msgs::Vector3
directionVector_
;
28
29
// relative position of the "lid" of the bottle in the end effector reference frame.
30
// that point is the one that must do the linear motion
31
geometry_msgs::Pose
pointerRelativePose_
;
32
protected
:
33
geometry_msgs::Point
relativePivotPoint_
;
34
35
// distance in meters from the initial pose to the bottom/top direction in z axe
36
double
deltaHeight_
;
37
38
std::vector<geometry_msgs::PoseStamped>
pointerTrajectory_
;
39
40
private
:
41
void
computeCurrentEndEffectorPoseRelativeToPivot
();
42
43
std::string
globalFrame_
;
44
};
45
46
}
// namespace cl_move_group_interface
cb_move_end_effector_trajectory.h
cl_move_group_interface::CbCircularPouringMotion
Definition:
cb_pouring_motion.h:15
cl_move_group_interface::CbCircularPouringMotion::globalFrame_
std::string globalFrame_
Definition:
cb_pouring_motion.h:43
cl_move_group_interface::CbCircularPouringMotion::createMarkers
virtual void createMarkers() override
Definition:
cb_pouring_motion.cpp:118
cl_move_group_interface::CbCircularPouringMotion::computeCurrentEndEffectorPoseRelativeToPivot
void computeCurrentEndEffectorPoseRelativeToPivot()
cl_move_group_interface::CbCircularPouringMotion::directionVector_
geometry_msgs::Vector3 directionVector_
Definition:
cb_pouring_motion.h:27
cl_move_group_interface::CbCircularPouringMotion::pointerRelativePose_
geometry_msgs::Pose pointerRelativePose_
Definition:
cb_pouring_motion.h:31
cl_move_group_interface::CbCircularPouringMotion::relativePivotPoint_
geometry_msgs::Point relativePivotPoint_
Definition:
cb_pouring_motion.h:33
cl_move_group_interface::CbCircularPouringMotion::pointerTrajectory_
std::vector< geometry_msgs::PoseStamped > pointerTrajectory_
Definition:
cb_pouring_motion.h:38
cl_move_group_interface::CbCircularPouringMotion::deltaHeight_
double deltaHeight_
Definition:
cb_pouring_motion.h:36
cl_move_group_interface::CbCircularPouringMotion::angularSpeed_rad_s_
boost::optional< double > angularSpeed_rad_s_
Definition:
cb_pouring_motion.h:17
cl_move_group_interface::CbCircularPouringMotion::generateTrajectory
virtual void generateTrajectory() override
Definition:
cb_pouring_motion.cpp:21
cl_move_group_interface::CbCircularPouringMotion::linearSpeed_m_s_
boost::optional< double > linearSpeed_m_s_
Definition:
cb_pouring_motion.h:19
cl_move_group_interface::CbMoveEndEffectorTrajectory
Definition:
cb_move_end_effector_trajectory.h:37
cl_move_group_interface
Definition:
cl_movegroup.h:19
Generated by
1.9.5