#include <cb_move_last_trajectory_initial_state.hpp>
◆ CbMoveLastTrajectoryInitialState() [1/2]
cl_move_group_interface::CbMoveLastTrajectoryInitialState::CbMoveLastTrajectoryInitialState |
( |
| ) |
|
◆ CbMoveLastTrajectoryInitialState() [2/2]
cl_move_group_interface::CbMoveLastTrajectoryInitialState::CbMoveLastTrajectoryInitialState |
( |
int |
backIndex | ) |
|
◆ ~CbMoveLastTrajectoryInitialState()
cl_move_group_interface::CbMoveLastTrajectoryInitialState::~CbMoveLastTrajectoryInitialState |
( |
| ) |
|
|
virtual |
◆ onEntry()
void cl_move_group_interface::CbMoveLastTrajectoryInitialState::onEntry |
( |
| ) |
|
|
overridevirtual |
Reimplemented from cl_move_group_interface::CbMoveJoints.
Definition at line 35 of file cb_move_last_trajectory_initial_state.cpp.
36{
37 CpTrajectoryHistory * trajectoryHistory;
39
40 if (trajectoryHistory != nullptr)
41 {
42 moveit_msgs::msg::RobotTrajectory trajectory;
43
44 bool trajectoryFound = trajectoryHistory->getLastTrajectory(
backIndex_, trajectory);
45
46 if (trajectoryFound)
47 {
48 trajectory_msgs::msg::JointTrajectoryPoint & initialPoint =
49 trajectory.joint_trajectory.points.front();
50
51 std::stringstream ss;
52 for (size_t i = 0; i < trajectory.joint_trajectory.joint_names.size(); i++)
53 {
54 auto & name = trajectory.joint_trajectory.joint_names[i];
55
58 }
59 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"]" << std::endl << ss.str());
60
61 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] move joint onEntry");
63 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] move joint onEntry finished");
64 }
65 }
66
67
68}
virtual void onEntry() override
std::map< std::string, double > jointValueTarget_
std::string getName() const
virtual rclcpp::Logger getLogger()
void requiresComponent(SmaccComponentType *&storage)
References backIndex_, cl_move_group_interface::CpTrajectoryHistory::getLastTrajectory(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), cl_move_group_interface::CbMoveJoints::jointValueTarget_, cl_move_group_interface::CbMoveJoints::onEntry(), and smacc2::ISmaccClientBehavior::requiresComponent().
◆ backIndex_
int cl_move_group_interface::CbMoveLastTrajectoryInitialState::backIndex_ = -1 |
|
private |
The documentation for this class was generated from the following files: