@@ -25,18 +25,18 @@ RaiManipulationInterfaceNode::RaiManipulationInterfaceNode()
25
25
void RaiManipulationInterfaceNode::Initialize (ArmController &arm) {
26
26
auto logger = m_node->get_logger ();
27
27
28
- auto current_pose = arm.GetEffectorPose ();
29
- auto [current_x, current_y, current_z, current_rx, current_ry, current_rz ] =
30
- std::make_tuple (current_pose [0 ], current_pose [1 ], current_pose [2 ],
31
- current_pose [3 ], current_pose [4 ], current_pose [5 ]);
28
+ auto currentPose = arm.GetEffectorPose ();
29
+ auto [currentX, currentY, currentZ, currentRX, currentRY, currentRZ ] =
30
+ std::make_tuple (currentPose [0 ], currentPose [1 ], currentPose [2 ],
31
+ currentPose [3 ], currentPose [4 ], currentPose [5 ]);
32
32
33
- auto current_gripper_state = arm.GetGripper ();
33
+ auto currentGripperState = arm.GetGripper ();
34
34
35
35
m_startingPose = arm.CaptureJointValues ();
36
36
37
- RCLCPP_INFO (logger, " Current pose: %f %f %f %f %f %f" , current_x, current_y ,
38
- current_z, current_rx, current_ry, current_rz );
39
- RCLCPP_INFO (logger, " Current gripper state: %d" , current_gripper_state );
37
+ RCLCPP_INFO (logger, " Current pose: %f %f %f %f %f %f" , currentX, currentY ,
38
+ currentRZ, currentRX, currentRY, currentRZ );
39
+ RCLCPP_INFO (logger, " Current gripper state: %d" , currentGripperState );
40
40
41
41
m_moveToService = m_node->create_service <
42
42
rai_interfaces::srv::ManipulatorMoveTo>(
@@ -54,14 +54,13 @@ void RaiManipulationInterfaceNode::Initialize(ArmController &arm) {
54
54
request->target_pose .header .frame_id .c_str ());
55
55
56
56
// Print current pose
57
- auto current_pose = arm.GetEffectorPose ();
58
- auto [current_x, current_y, current_z, current_rx, current_ry,
59
- current_rz] =
60
- std::make_tuple (current_pose[0 ], current_pose[1 ], current_pose[2 ],
61
- current_pose[3 ], current_pose[4 ], current_pose[5 ]);
62
-
63
- RCLCPP_INFO (logger, " Current pose: %f %f %f %f %f %f" , current_x,
64
- current_y, current_z, current_rx, current_ry, current_rz);
57
+ auto currentPose = arm.GetEffectorPose ();
58
+ auto [currentX, currentY, currentZ, currentRX, currentRY, currentRZ] =
59
+ std::make_tuple (currentPose[0 ], currentPose[1 ], currentPose[2 ],
60
+ currentPose[3 ], currentPose[4 ], currentPose[5 ]);
61
+
62
+ RCLCPP_INFO (logger, " Current pose: %f %f %f %f %f %f" , currentX,
63
+ currentY, currentRZ, currentRX, currentRY, currentRZ);
65
64
RCLCPP_INFO (logger, " Target pose: %f %f %f %f %f %f" ,
66
65
request->target_pose .pose .position .x ,
67
66
request->target_pose .pose .position .y ,
@@ -79,24 +78,24 @@ void RaiManipulationInterfaceNode::Initialize(ArmController &arm) {
79
78
{
80
79
using std::min;
81
80
using std::max;
82
- auto current_pose = arm.GetEffectorPose ();
83
- auto above_current = current_pose ;
84
- auto calculate_z_above_target = [&](double target_z ) {
85
- double const minimum_z = 0.3 ;
86
- double const maximum_z = 0.4 ;
87
- double const z_offset = 0.1 ;
88
-
89
- return min (maximum_z , max (target_z + z_offset, minimum_z ));
81
+ auto currentPose = arm.GetEffectorPose ();
82
+ auto aboveCurrent = currentPose ;
83
+ auto calculateZAboveTarget = [&](double targetZ ) {
84
+ double const MinimumZ = 0.3 ;
85
+ double const MaximumZ = 0.4 ;
86
+ double const ZOffset = 0.1 ;
87
+
88
+ return min (MaximumZ , max (targetZ + ZOffset, MinimumZ ));
90
89
};
91
- above_current [2 ] = calculate_z_above_target (above_current [2 ]);
92
- auto above_target = request->target_pose .pose ;
90
+ aboveCurrent [2 ] = calculateZAboveTarget (aboveCurrent [2 ]);
91
+ auto aboveTarget = request->target_pose .pose ;
93
92
94
- above_target .position .z =
95
- calculate_z_above_target (above_target .position .z );
93
+ aboveTarget .position .z =
94
+ calculateZAboveTarget (aboveTarget .position .z );
96
95
if (!arm.MoveThroughWaypoints (
97
- {arm.CalculatePose (above_current [0 ], above_current [1 ],
98
- above_current [2 ]),
99
- above_target , request->target_pose .pose }))
96
+ {arm.CalculatePose (aboveCurrent [0 ], aboveCurrent [1 ],
97
+ aboveCurrent [2 ]),
98
+ aboveTarget , request->target_pose .pose }))
100
99
return ;
101
100
102
101
if (request->final_gripper_state ) {
0 commit comments