This commit is contained in:
Sem van der Hoeven
2023-06-12 15:34:03 +02:00
parent f23e56a9a0
commit 21683cb92c
2 changed files with 5 additions and 5 deletions

View File

@@ -225,7 +225,7 @@ public:
{ {
if (!this->move_direction_allowed[MOVE_DIRECTION_FRONT]) if (!this->move_direction_allowed[MOVE_DIRECTION_FRONT])
{ {
RCLCPP_INFO(this->get_logger(), "Collision prevention front: %d", collision_prevention_weights[MOVE_DIRECTION_FRONT]); RCLCPP_INFO(this->get_logger(), "Collision prevention front: %f", collision_prevention_weights[MOVE_DIRECTION_FRONT]);
get_x_y_with_rotation(collision_prevention_weights[MOVE_DIRECTION_FRONT], 0, this->current_yaw, &this->current_speed_x, &this->current_speed_y); get_x_y_with_rotation(collision_prevention_weights[MOVE_DIRECTION_FRONT], 0, this->current_yaw, &this->current_speed_x, &this->current_speed_y);
} }
} }
@@ -233,7 +233,7 @@ public:
{ {
if (!this->move_direction_allowed[MOVE_DIRECTION_BACK]) if (!this->move_direction_allowed[MOVE_DIRECTION_BACK])
{ {
RCLCPP_INFO(this->get_logger(), "Collision prevention back: %d", collision_prevention_weights[MOVE_DIRECTION_BACK]); RCLCPP_INFO(this->get_logger(), "Collision prevention back: %f", collision_prevention_weights[MOVE_DIRECTION_BACK]);
get_x_y_with_rotation(collision_prevention_weights[MOVE_DIRECTION_BACK], 0, this->current_yaw, &this->current_speed_x, &this->current_speed_y); get_x_y_with_rotation(collision_prevention_weights[MOVE_DIRECTION_BACK], 0, this->current_yaw, &this->current_speed_x, &this->current_speed_y);
} }
} }
@@ -241,7 +241,7 @@ public:
{ {
if (!this->move_direction_allowed[MOVE_DIRECTION_RIGHT]) if (!this->move_direction_allowed[MOVE_DIRECTION_RIGHT])
{ {
RCLCPP_INFO(this->get_logger(), "Collision prevention right: %d", collision_prevention_weights[MOVE_DIRECTION_RIGHT]); RCLCPP_INFO(this->get_logger(), "Collision prevention right: %f", collision_prevention_weights[MOVE_DIRECTION_RIGHT]);
get_x_y_with_rotation(0, collision_prevention_weights[MOVE_DIRECTION_RIGHT], this->current_yaw, &this->current_speed_x, &this->current_speed_y); get_x_y_with_rotation(0, collision_prevention_weights[MOVE_DIRECTION_RIGHT], this->current_yaw, &this->current_speed_x, &this->current_speed_y);
} }
} }
@@ -249,7 +249,7 @@ public:
{ {
if (!this->move_direction_allowed[MOVE_DIRECTION_LEFT]) if (!this->move_direction_allowed[MOVE_DIRECTION_LEFT])
{ {
RCLCPP_INFO(this->get_logger(), "Collision prevention left: %d", collision_prevention_weights[MOVE_DIRECTION_LEFT]); RCLCPP_INFO(this->get_logger(), "Collision prevention left: %f", collision_prevention_weights[MOVE_DIRECTION_LEFT]);
get_x_y_with_rotation(0, collision_prevention_weights[MOVE_DIRECTION_LEFT], this->current_yaw, &this->current_speed_x, &this->current_speed_y); get_x_y_with_rotation(0, collision_prevention_weights[MOVE_DIRECTION_LEFT], this->current_yaw, &this->current_speed_x, &this->current_speed_y);
} }
} }

View File

@@ -99,7 +99,7 @@ class TestPositionChanger(unittest.TestCase):
if not self.called_positionchanger_service: if not self.called_positionchanger_service:
future = move_position_client.call_async(request) future = move_position_client.call_async(request)
future.add_done_callback(self.move_position_callback) future.add_done_callback(self.move_position_callback)
launch_testing.asserts.assertInStdout(proc_output, "Collision prevention back", 'px4_controller-3') launch_testing.asserts.assertInStdout(proc_output, "Collision prevention front", 'px4_controller-3')
finally: finally:
self.node.destroy_client(move_position_client) self.node.destroy_client(move_position_client)
self.node.destroy_publisher(lidar_publisher) self.node.destroy_publisher(lidar_publisher)