15
15
16
16
#include " robotic_manipulation/arm_controller.h"
17
17
18
- #include < rosgraph_msgs/msg/clock.hpp>
19
-
20
18
#include < numbers>
19
+ #include < rosgraph_msgs/msg/clock.hpp>
21
20
22
- void ArmController::Initialize () {
21
+ void ArmController::Initialize ()
22
+ {
23
23
m_node = rclcpp::Node::make_shared (" arm_controller" );
24
24
m_node->set_parameter (rclcpp::Parameter (" use_sim_time" , true ));
25
25
@@ -28,32 +28,31 @@ void ArmController::Initialize() {
28
28
m_executor.add_node (m_node);
29
29
m_spinner = std::thread ([this ]() { m_executor.spin (); });
30
30
31
- m_pandaArm = std::make_shared<moveit::planning_interface::MoveGroupInterface>(
32
- m_node, " panda_arm" );
33
- m_hand = std::make_shared<moveit::planning_interface::MoveGroupInterface>(
34
- m_node, " hand" );
31
+ m_pandaArm =
32
+ std::make_shared<moveit::planning_interface::MoveGroupInterface>(m_node, " panda_arm" );
33
+ m_hand = std::make_shared<moveit::planning_interface::MoveGroupInterface>(m_node, " hand" );
35
34
36
35
m_pandaArm->setMaxVelocityScalingFactor (1.0 );
37
36
m_pandaArm->setMaxAccelerationScalingFactor (1.0 );
38
37
}
39
38
40
- ArmController::~ArmController () {
39
+ ArmController::~ArmController ()
40
+ {
41
41
m_executor.cancel ();
42
42
if (m_spinner.joinable ()) {
43
43
m_spinner.join ();
44
44
}
45
45
}
46
46
47
- geometry_msgs::msg::Pose ArmController::CalculatePose (double x, double y,
48
- double z, double r) {
47
+ geometry_msgs::msg::Pose ArmController::CalculatePose (double x, double y, double z, double r)
48
+ {
49
49
geometry_msgs::msg::Pose pose;
50
50
pose.position .x = x;
51
51
pose.position .y = y;
52
52
pose.position .z = z;
53
53
54
54
auto quat = tf2::Quaternion ();
55
- quat.setEuler (EndEffectorBaseRoll, EndEffectorBasePitch,
56
- EndEffectorBaseYaw + r);
55
+ quat.setEuler (EndEffectorBaseRoll, EndEffectorBasePitch, EndEffectorBaseYaw + r);
57
56
pose.orientation .x = quat.x ();
58
57
pose.orientation .y = quat.y ();
59
58
pose.orientation .z = quat.z ();
@@ -62,72 +61,75 @@ geometry_msgs::msg::Pose ArmController::CalculatePose(double x, double y,
62
61
return pose;
63
62
}
64
63
65
- bool ArmController::MoveThroughWaypoints (
66
- std::vector<geometry_msgs::msg::Pose> const &waypoints) {
64
+ bool ArmController::MoveThroughWaypoints (std::vector<geometry_msgs::msg::Pose> const & waypoints)
65
+ {
67
66
auto logger = m_node->get_logger ();
68
67
69
68
int constexpr NumTries = 10 ;
70
69
for (int i = 0 ; i < NumTries; i++) {
71
70
moveit_msgs::msg::RobotTrajectory trajectory;
72
- if (m_pandaArm->computeCartesianPath (waypoints, 0.01 , 0.0 , trajectory) ==
73
- -1 ) {
74
- RCLCPP_ERROR (logger,
75
- " MoveThroughWaypoints: Failed to compute Cartesian path" );
71
+ if (m_pandaArm->computeCartesianPath (waypoints, 0.01 , 0.0 , trajectory) == -1 ) {
72
+ RCLCPP_ERROR (logger, " MoveThroughWaypoints: Failed to compute Cartesian path" );
76
73
continue ;
77
74
}
78
75
79
- if (m_pandaArm->execute (trajectory) ==
80
- moveit::core::MoveItErrorCode::SUCCESS) {
76
+ if (m_pandaArm->execute (trajectory) == moveit::core::MoveItErrorCode::SUCCESS) {
81
77
return true ;
82
78
}
83
- RCLCPP_ERROR (logger, " MoveThroughWaypoints: Failed to execute "
84
- " trajectory, trying again..." );
79
+ RCLCPP_ERROR (
80
+ logger,
81
+ " MoveThroughWaypoints: Failed to execute "
82
+ " trajectory, trying again..." );
85
83
}
86
84
87
85
RCLCPP_ERROR (
88
- logger,
89
- " MoveThroughWaypoints: Failed to execute trajectory after %d tries" ,
90
- NumTries);
86
+ logger, " MoveThroughWaypoints: Failed to execute trajectory after %d tries" , NumTries);
91
87
return false ;
92
88
}
93
89
94
- void ArmController::Open () {
90
+ void ArmController::Open ()
91
+ {
95
92
gripper.store (true );
96
93
m_hand->setJointValueTarget (" panda_finger_joint1" , OpenGripperJointValue);
97
94
while (m_hand->move () != moveit::core::MoveItErrorCode::SUCCESS) {
98
95
RCLCPP_ERROR (m_node->get_logger (), " Failed to open hand" );
99
96
}
100
97
}
101
98
102
- void ArmController::Close () {
99
+ void ArmController::Close ()
100
+ {
103
101
gripper.store (false );
104
102
m_hand->setJointValueTarget (" panda_finger_joint1" , ClosedGripperJointValue);
105
103
while (m_hand->move () != moveit::core::MoveItErrorCode::SUCCESS) {
106
104
RCLCPP_ERROR (m_node->get_logger (), " Failed to close hand" );
107
105
}
108
106
}
109
107
110
- std::vector<double > ArmController::GetEffectorPose () {
108
+ std::vector<double > ArmController::GetEffectorPose ()
109
+ {
111
110
auto pose = m_pandaArm->getCurrentPose ().pose ;
112
- auto rotation = tf2::Quaternion (pose. orientation . x , pose. orientation . y ,
113
- pose.orientation .z , pose.orientation .w );
111
+ auto rotation =
112
+ tf2::Quaternion (pose. orientation . x , pose. orientation . y , pose.orientation .z , pose.orientation .w );
114
113
tf2::Matrix3x3 m (rotation);
115
114
m.getRPY (pose.orientation .x , pose.orientation .y , pose.orientation .z , 0 );
116
- return {pose.position .x ,
117
- pose.position .y ,
118
- pose.position .z ,
119
- pose.orientation .x ,
120
- pose.orientation .y - EndEffectorBasePitch,
121
- pose.orientation .z - (tf2Radians (180.0 ) - EndEffectorBaseYaw)};
115
+ return {
116
+ pose.position .x ,
117
+ pose.position .y ,
118
+ pose.position .z ,
119
+ pose.orientation .x ,
120
+ pose.orientation .y - EndEffectorBasePitch,
121
+ pose.orientation .z - (tf2Radians (180.0 ) - EndEffectorBaseYaw)};
122
122
};
123
123
124
124
bool ArmController::GetGripper () { return gripper.load (); }
125
125
126
- std::vector<double > ArmController::CaptureJointValues () {
126
+ std::vector<double > ArmController::CaptureJointValues ()
127
+ {
127
128
return m_pandaArm->getCurrentJointValues ();
128
129
}
129
130
130
- bool ArmController::SetJointValues (std::vector<double > const &jointValues) {
131
+ bool ArmController::SetJointValues (std::vector<double > const & jointValues)
132
+ {
131
133
m_pandaArm->setJointValueTarget (jointValues);
132
134
if (m_pandaArm->move () != moveit::core::MoveItErrorCode::SUCCESS) {
133
135
RCLCPP_ERROR (m_node->get_logger (), " Failed to set joint values" );
@@ -136,17 +138,18 @@ bool ArmController::SetJointValues(std::vector<double> const &jointValues) {
136
138
return true ;
137
139
}
138
140
139
- void ArmController::SetReferenceFrame (std::string const &frame) {
141
+ void ArmController::SetReferenceFrame (std::string const & frame)
142
+ {
140
143
m_pandaArm->setPoseReferenceFrame (frame);
141
144
}
142
145
143
- void ArmController::WaitForClockMessage () {
146
+ void ArmController::WaitForClockMessage ()
147
+ {
144
148
bool clockReceived = false ;
145
149
auto qos = rclcpp::QoS (rclcpp::KeepLast (1 ));
146
150
qos.best_effort ();
147
151
auto subscription = m_node->create_subscription <rosgraph_msgs::msg::Clock>(
148
- " /clock" , qos,
149
- [&](rosgraph_msgs::msg::Clock::SharedPtr) { clockReceived = true ; });
152
+ " /clock" , qos, [&](rosgraph_msgs::msg::Clock::SharedPtr) { clockReceived = true ; });
150
153
while (!clockReceived) {
151
154
rclcpp::spin_some (m_node);
152
155
}
0 commit comments