Skip to content

Commit 206c68c

Browse files
knickedjhanca-robotecai
authored andcommitted
Rename variables for style consistency
Signed-off-by: Kacper Dąbrowski <[email protected]>
1 parent 2c0c6a5 commit 206c68c

File tree

2 files changed

+33
-34
lines changed

2 files changed

+33
-34
lines changed

ros2_ws/src/robotic_manipulation/src/arm_controller.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -151,13 +151,13 @@ void ArmController::SetReferenceFrame(std::string const &frame) {
151151
}
152152

153153
void ArmController::WaitForClockMessage() {
154-
bool clock_received = false;
154+
bool clockReceived = false;
155155
auto qos = rclcpp::QoS(rclcpp::KeepLast(1));
156156
qos.best_effort();
157157
auto subscription = m_node->create_subscription<rosgraph_msgs::msg::Clock>(
158158
"/clock", qos,
159-
[&](rosgraph_msgs::msg::Clock::SharedPtr) { clock_received = true; });
160-
while (!clock_received) {
159+
[&](rosgraph_msgs::msg::Clock::SharedPtr) { clockReceived = true; });
160+
while (!clockReceived) {
161161
rclcpp::spin_some(m_node);
162162
}
163163
subscription.reset();

ros2_ws/src/robotic_manipulation/src/rai_manipulation_interface_node.cpp

+30-31
Original file line numberDiff line numberDiff line change
@@ -25,18 +25,18 @@ RaiManipulationInterfaceNode::RaiManipulationInterfaceNode()
2525
void RaiManipulationInterfaceNode::Initialize(ArmController &arm) {
2626
auto logger = m_node->get_logger();
2727

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]);
3232

33-
auto current_gripper_state = arm.GetGripper();
33+
auto currentGripperState = arm.GetGripper();
3434

3535
m_startingPose = arm.CaptureJointValues();
3636

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);
4040

4141
m_moveToService = m_node->create_service<
4242
rai_interfaces::srv::ManipulatorMoveTo>(
@@ -54,14 +54,13 @@ void RaiManipulationInterfaceNode::Initialize(ArmController &arm) {
5454
request->target_pose.header.frame_id.c_str());
5555

5656
// 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);
6564
RCLCPP_INFO(logger, "Target pose: %f %f %f %f %f %f",
6665
request->target_pose.pose.position.x,
6766
request->target_pose.pose.position.y,
@@ -79,24 +78,24 @@ void RaiManipulationInterfaceNode::Initialize(ArmController &arm) {
7978
{
8079
using std::min;
8180
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));
9089
};
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;
9392

94-
above_target.position.z =
95-
calculate_z_above_target(above_target.position.z);
93+
aboveTarget.position.z =
94+
calculateZAboveTarget(aboveTarget.position.z);
9695
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}))
10099
return;
101100

102101
if (request->final_gripper_state) {

0 commit comments

Comments
 (0)