Skip to content

Commit

Permalink
Uncrustify run without lambdas
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
  • Loading branch information
luca-della-vedova committed Nov 12, 2024
1 parent 425c47c commit d57a63c
Show file tree
Hide file tree
Showing 36 changed files with 266 additions and 210 deletions.
5 changes: 3 additions & 2 deletions nexus_capabilities/src/capabilities/detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ bool DetectOffset::on_response(
pose.pose = found_detection->bbox.center;
RCLCPP_DEBUG_STREAM(this->_logger,
*item << " is at " << pose.pose << " frame [" << pose.header.frame_id <<
"]");
"]");
this->setOutput("result", pose);
return true;
}
Expand Down Expand Up @@ -171,7 +171,8 @@ BT::NodeStatus DetectAllItems::onRunning()
if (d.id != *this->_cur_it)
{
RCLCPP_WARN(
this->_node->get_logger(), "detector requested to detect [%s] but it responded with [%s], ignoring the result",
this->_node->get_logger(),
"detector requested to detect [%s] but it responded with [%s], ignoring the result",
this->_cur_it->c_str(), d.id.c_str());
continue;
}
Expand Down
24 changes: 14 additions & 10 deletions nexus_capabilities/src/capabilities/detection_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,15 +63,17 @@ void DetectionCapability::configure(
auto node = w_node.lock();
if (!node)
{
std::cerr << "FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!" << std::endl;
std::cerr <<
"FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!"
<< std::endl;
std::terminate();
}

return std::make_unique<DetectOffset>(name, config,
node->get_logger(), ctx_mgr, [this, node](const std::string& detector)
{
return this->_clients.at(detector);
});
node->get_logger(), ctx_mgr, [this, node](const std::string& detector)
{
return this->_clients.at(detector);
});
});

bt_factory.registerBuilder<DetectAllItems>(
Expand All @@ -82,15 +84,17 @@ void DetectionCapability::configure(
auto node = w_node.lock();
if (!node)
{
std::cerr << "FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!" << std::endl;
std::cerr <<
"FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!"
<< std::endl;
std::terminate();
}

return std::make_unique<DetectAllItems>(name, config, node, ctx_mgr,
[this](const std::string& detector)
{
return this->_clients.at(detector);
});
[this](const std::string& detector)
{
return this->_clients.at(detector);
});
});

bt_factory.registerBuilder<GetDetection>(
Expand Down
3 changes: 2 additions & 1 deletion nexus_capabilities/src/capabilities/dispense_item.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,8 @@ protected: endpoints::DispenserService::ServiceType::Request::SharedPtr
make_request() final;

protected: bool on_response(
rclcpp::Client<endpoints::DispenserService::ServiceType>::SharedResponse resp)
rclcpp::Client<endpoints::DispenserService::ServiceType>::SharedResponse
resp)
final;

private: std::vector<DispenserSession> _dispensers;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ void DispenseItemCapability::declare_params(
//==============================================================================
void DispenseItemCapability::configure(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
std::shared_ptr<const ContextManager> /* ctx_mgr */,
std::shared_ptr<const ContextManager>/* ctx_mgr */,
BT::BehaviorTreeFactory& bt_factory)
{
auto dispenser_ids = node->get_parameter("dispensers").as_string_array();
Expand All @@ -74,7 +74,7 @@ void DispenseItemCapability::configure(
{
auto node = w_node.lock();
return std::make_unique<DispenseItem>(name, config,
node, this->_dispensers, std::chrono::milliseconds{dispenser_timeout});
node, this->_dispensers, std::chrono::milliseconds{dispenser_timeout});
});
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace nexus::capabilities {

void ExecuteTrajectoryCapability::configure(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
std::shared_ptr<const ContextManager> /* ctx_mgr */,
std::shared_ptr<const ContextManager>/* ctx_mgr */,
BT::BehaviorTreeFactory& bt_factory)
{
bt_factory.registerBuilder<ExecuteTrajectory>(
Expand All @@ -38,7 +38,9 @@ void ExecuteTrajectoryCapability::configure(
auto node = w_node.lock();
if (!node)
{
std::cerr << "FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!" << std::endl;
std::cerr <<
"FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!"
<< std::endl;
std::terminate();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,8 @@
*
*/

#ifndef \
NEXUS_CAPABILITIES__CAPABILITIES__EXECUTE_TRAJECTORY_CAPABILITY_HPP
#define \
NEXUS_CAPABILITIES__CAPABILITIES__EXECUTE_TRAJECTORY_CAPABILITY_HPP
#ifndef NEXUS_CAPABILITIES__CAPABILITIES__EXECUTE_TRAJECTORY_CAPABILITY_HPP
#define NEXUS_CAPABILITIES__CAPABILITIES__EXECUTE_TRAJECTORY_CAPABILITY_HPP

#include <nexus_capabilities/capability.hpp>
#include <nexus_capabilities/context_manager.hpp>
Expand Down
2 changes: 1 addition & 1 deletion nexus_capabilities/src/capabilities/gripper_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ void GripperCapability::declare_params(rclcpp_lifecycle::LifecycleNode& node)

void GripperCapability::configure(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
std::shared_ptr<const ContextManager> /* ctx_mgr */,
std::shared_ptr<const ContextManager>/* ctx_mgr */,
BT::BehaviorTreeFactory& bt_factory)
{
auto grippers = node->get_parameter("grippers").as_string_array();
Expand Down
7 changes: 4 additions & 3 deletions nexus_capabilities/src/capabilities/plan_motion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,14 +133,15 @@ make_request()

RCLCPP_DEBUG_STREAM(this->_logger,
"planning to " << req->goal_pose.pose << " at frame " <<
req->goal_pose.header.frame_id << " with cartesian " << req->cartesian << "and scaled speed of " <<
scale_speed);
req->goal_pose.header.frame_id << " with cartesian " << req->cartesian <<
"and scaled speed of " << scale_speed);

return req;
}

bool PlanMotion::on_response(
rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::SharedResponse resp)
rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::SharedResponse
resp)
{
if (resp->result.error_code.val !=
moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
Expand Down
6 changes: 4 additions & 2 deletions nexus_capabilities/src/capabilities/plan_motion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,8 @@ public: static BT::PortsList providedPorts()
public: PlanMotion(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp_lifecycle::LifecycleNode& node,
rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::SharedPtr client,
rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::SharedPtr
client,
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster)
: ServiceClientBtNode<endpoints::GetMotionPlanService::ServiceType>(name,
config, node.get_logger(), std::chrono::minutes{1}), _node{node},
Expand All @@ -100,7 +101,8 @@ protected: endpoints::GetMotionPlanService::ServiceType::Request::SharedPtr
make_request() final;

protected: bool on_response(
rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::SharedResponse resp)
rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::SharedResponse
resp)
final;

private: rclcpp_lifecycle::LifecycleNode& _node;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace nexus::capabilities {

void PlanMotionCapability::configure(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
std::shared_ptr<const ContextManager> /* ctx_mgr */,
std::shared_ptr<const ContextManager>/* ctx_mgr */,
BT::BehaviorTreeFactory& bt_factory)
{
this->_client =
Expand All @@ -41,7 +41,7 @@ void PlanMotionCapability::configure(
const BT::NodeConfiguration& config)
{
return std::make_unique<PlanMotion>(name, config, *node, this->_client,
tf_broadcaster);
tf_broadcaster);
});
}

Expand Down
5 changes: 3 additions & 2 deletions nexus_common/include/nexus_common/action_client_bt_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,8 @@ protected: virtual void on_feedback(typename ActionT::Feedback::ConstSharedPtr);
* the action is considered a success and false otherwise.
*/
protected: virtual bool on_result(
const typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult& result);
const typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult&
result);

private: rclcpp::executors::SingleThreadedExecutor _executor;
private: rclcpp::CallbackGroup::SharedPtr _cb_group;
Expand Down Expand Up @@ -131,7 +132,7 @@ BT::NodeStatus ActionClientBtNode<NodePtrT, ActionT>::onStart()
typename rclcpp_action::Client<ActionT>::SendGoalOptions options;
options.feedback_callback =
[this](typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr,
typename ActionT::Feedback::ConstSharedPtr feedback)
typename ActionT::Feedback::ConstSharedPtr feedback)
{
this->on_feedback(feedback);
};
Expand Down
2 changes: 1 addition & 1 deletion nexus_common/include/nexus_common/batch_service_call.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ struct BatchServiceResult
*/
template<typename NodePtrT, typename ServiceT, typename KeyT,
typename DoneCallbackT = std::function<void(const std::unordered_map<KeyT,
BatchServiceResult<ServiceT>>&)>>
BatchServiceResult<ServiceT>>& )>>
CancellationToken batch_service_call(
NodePtrT node,
const std::unordered_map<KeyT, BatchServiceReq<ServiceT>>& batch_reqs,
Expand Down
37 changes: 24 additions & 13 deletions nexus_common/src/action_client_bt_node_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@ public: static BT::PortsList providedPorts()

public: TestActionBtNode(const std::string& name,
const BT::NodeConfiguration& config, rclcpp::Node::SharedPtr node,
rclcpp_action::Client<example_interfaces::action::Fibonacci>::SharedPtr client)
rclcpp_action::Client<example_interfaces::action::Fibonacci>::SharedPtr
client)
: ActionClientBtNode<rclcpp::Node::SharedPtr,
example_interfaces::action::Fibonacci>(name, config, node),
_client(client) {}
Expand Down Expand Up @@ -116,13 +117,15 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
return rclcpp_action::GoalResponse::REJECT;
},
[&](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>)
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>)
{
rejected_goal.set_value();
return rclcpp_action::CancelResponse::REJECT;
},
[](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>
handle)
{
handle->abort(
Expand All @@ -145,12 +148,14 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>)
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>)
{
return rclcpp_action::CancelResponse::REJECT;
},
[](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>
handle)
{
handle->abort(
Expand Down Expand Up @@ -178,13 +183,15 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[&](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>)
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>)
{
got_cancel.set_value();
return rclcpp_action::CancelResponse::ACCEPT;
},
[&](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>
handle)
{
started_job.set_value();
Expand All @@ -202,7 +209,7 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
tick_until(bt, [&](auto)
{
return started_job_fut.wait_for(std::chrono::seconds(
0)) == std::future_status::ready;
0)) == std::future_status::ready;
}, std::chrono::seconds(1));
bt.haltTree();
CHECK(got_cancel_fut.wait_for(std::chrono::seconds(0)) ==
Expand All @@ -225,12 +232,14 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[&](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>)
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>)
{
return rclcpp_action::CancelResponse::REJECT;
},
[&](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>
handle)
{
started_job.set_value();
Expand All @@ -247,7 +256,7 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
tick_until(bt, [&](auto)
{
return started_job_fut.wait_for(std::chrono::seconds(
0)) == std::future_status::ready;
0)) == std::future_status::ready;
}, std::chrono::seconds(1));

// test action takes 1 second, halting the tree should cause it to block until
Expand All @@ -270,12 +279,14 @@ TEST_CASE("ActionClientBtNode", "[BehaviorTree]")
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>)
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>)
{
return rclcpp_action::CancelResponse::REJECT;
},
[](
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::action::Fibonacci>>
std::shared_ptr<rclcpp_action::ServerGoalHandle<example_interfaces::
action::Fibonacci>>
handle)
{
handle->succeed(
Expand Down
3 changes: 2 additions & 1 deletion nexus_common/src/models/work_order_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@ TEST_CASE("WorkOrder serialization", "[Model][Serialization]")
}
)RAW"};

auto check_data = [](const WorkOrder& work_order)
auto check_data =
[](const WorkOrder& work_order)
{
CHECK(work_order.number() == "SO/2022/20/1-1");
CHECK(work_order.work_instruction_name() == "CV-299 (Rev 4)");
Expand Down
3 changes: 2 additions & 1 deletion nexus_common/src/node_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,8 @@ get_node_options_default(bool allow_undeclared, bool declare_initial_params)
{
rclcpp::NodeOptions options;
options.allow_undeclared_parameters(allow_undeclared);
options.automatically_declare_parameters_from_overrides(declare_initial_params);
options.automatically_declare_parameters_from_overrides(
declare_initial_params);
return options;
}

Expand Down
2 changes: 1 addition & 1 deletion nexus_gazebo/include/nexus_gazebo/Components.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace nexus_gazebo::components {
using MotionCaptureRigidBody = gz::sim::components::Component<
std::string,
class MotionCaptureRigidBodyTag,
gz::sim::serializers::StringSerializer>;
gz::sim::serializers::StringSerializer>;

GZ_SIM_REGISTER_COMPONENT(
"nexus_gazebo.components.MotionCaptureRigidBody",
Expand Down
4 changes: 2 additions & 2 deletions nexus_integration_tests/src/mock_transporter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,8 +269,8 @@ class MockTransporter : public Transporter

state.location.pose.position.x += x_increment;
dist_traveled += abs(x_increment);
_transporters.at(
current_transporter)->current_location.pose = state.location.pose.position.x;
_transporters.at(current_transporter)->current_location.pose =
state.location.pose.position.x;
feedback_cb(state);
}

Expand Down
3 changes: 1 addition & 2 deletions nexus_integration_tests/src/test_mock_gripper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,7 @@ SCENARIO("Test Gripper Mock")
double end_position = 0.0;

auto goal_response_callback =
[&goal_response](GoalHandleGripperAction::SharedPtr
goal_handle)
[&goal_response](GoalHandleGripperAction::SharedPtr goal_handle)
{
if (goal_handle)
{
Expand Down
Loading

0 comments on commit d57a63c

Please sign in to comment.