Skip to content

Commit

Permalink
code style only: wrap after open parenthesis if not in one line (#429)
Browse files Browse the repository at this point in the history
Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
  • Loading branch information
dirk-thomas authored Feb 3, 2020
1 parent 003348c commit fab4fc3
Show file tree
Hide file tree
Showing 22 changed files with 130 additions and 81 deletions.
3 changes: 2 additions & 1 deletion composition/src/server_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ Server::Server(const rclcpp::NodeOptions & options)
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response
) -> void
{
RCLCPP_INFO(this->get_logger(), "Incoming request: [a: %" PRId64 ", b: %" PRId64 "]",
RCLCPP_INFO(
this->get_logger(), "Incoming request: [a: %" PRId64 ", b: %" PRId64 "]",
request->a, request->b);
std::flush(std::cout);
response->sum = request->a + request->b;
Expand Down
17 changes: 9 additions & 8 deletions demo_nodes_cpp/src/parameters/even_parameters_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,31 +42,32 @@ class EvenParameterNode : public rclcpp::Node
for (auto parameter : parameters) {
rclcpp::ParameterType parameter_type = parameter.get_type();
if (rclcpp::ParameterType::PARAMETER_NOT_SET == parameter_type) {
RCLCPP_INFO(this->get_logger(),
"parameter '%s' deleted successfully",
RCLCPP_INFO(
this->get_logger(), "parameter '%s' deleted successfully",
parameter.get_name().c_str()
);
result.successful &= true;
} else if (rclcpp::ParameterType::PARAMETER_INTEGER == parameter_type) {
if (parameter.as_int() % 2 != 0) {
RCLCPP_INFO(this->get_logger(),
"Requested value '%d' for parameter '%s' is not an even number:"
" rejecting change...",
RCLCPP_INFO(
this->get_logger(), "Requested value '%d' for parameter '%s' "
"is not an even number: rejecting change...",
parameter.as_int(),
parameter.get_name().c_str()
);
result.successful = false;
} else {
RCLCPP_INFO(this->get_logger(),
RCLCPP_INFO(
this->get_logger(),
"parameter '%s' has changed and is now: %s",
parameter.get_name().c_str(),
parameter.value_to_string().c_str()
);
result.successful &= true;
}
} else {
RCLCPP_INFO(this->get_logger(),
"only integer parameters can be set\n"
RCLCPP_INFO(
this->get_logger(), "only integer parameters can be set\n"
"requested value for parameter '%s' is not an even number, rejecting change...",
parameter.get_name().c_str()
);
Expand Down
3 changes: 2 additions & 1 deletion demo_nodes_cpp/src/parameters/list_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ class ListParameters : public rclcpp::Node

RCLCPP_INFO(this->get_logger(), "Setting parameters...");
// Set several different types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
auto set_parameters_results = parameters_client->set_parameters(
{
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
Expand Down
3 changes: 2 additions & 1 deletion demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ int main(int argc, char ** argv)

RCLCPP_INFO(node->get_logger(), "Setting parameters...");
// Set several differnet types of parameters.
auto results = parameters_client->set_parameters({
auto results = parameters_client->set_parameters(
{
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
Expand Down
3 changes: 2 additions & 1 deletion demo_nodes_cpp/src/parameters/parameter_blackboard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ class ParameterBlackboard : public rclcpp::Node
options.allow_undeclared_parameters(true).
automatically_declare_parameters_from_overrides(true))
{
RCLCPP_INFO(this->get_logger(),
RCLCPP_INFO(
this->get_logger(),
"Parameter blackboard node named '%s' ready, and serving '%zu' parameters already!",
this->get_fully_qualified_name(), this->list_parameters(
{}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE).names.size());
Expand Down
6 changes: 4 additions & 2 deletions demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,15 +84,17 @@ int main(int argc, char ** argv)
node->declare_parameter("foobar");

// Set several different types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
auto set_parameters_results = parameters_client->set_parameters(
{
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foobar", true),
});

// Change the value of some of them.
set_parameters_results = parameters_client->set_parameters({
set_parameters_results = parameters_client->set_parameters(
{
rclcpp::Parameter("foo", 3),
rclcpp::Parameter("bar", "world"),
});
Expand Down
24 changes: 14 additions & 10 deletions demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,10 +71,11 @@ class ParameterEventsAsyncNode : public rclcpp::Node

// Queue a `set_parameters` request as soon as `spin` is called on this node.
// TODO(dhood): consider adding a "call soon" notion to Node to not require a timer for this.
timer_ = create_wall_timer(200ms,
[this]() {
this->queue_first_set_parameter_request();
});
timer_ = create_wall_timer(
200ms,
[this]() {
this->queue_first_set_parameter_request();
});
}

private:
Expand All @@ -101,7 +102,8 @@ class ParameterEventsAsyncNode : public rclcpp::Node
this->queue_second_set_parameter_request();
};

parameters_client_->set_parameters({
parameters_client_->set_parameters(
{
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
Expand All @@ -123,12 +125,14 @@ class ParameterEventsAsyncNode : public rclcpp::Node
// TODO(wjwwood): Create and use delete_parameter

// Give time for all of the ParameterEvent callbacks to be received.
timer_ = create_wall_timer(100ms,
[]() {
rclcpp::shutdown();
});
timer_ = create_wall_timer(
100ms,
[]() {
rclcpp::shutdown();
});
};
parameters_client_->set_parameters({
parameters_client_->set_parameters(
{
rclcpp::Parameter("foo", 3),
rclcpp::Parameter("bar", "world"),
}, response_received_callback);
Expand Down
8 changes: 5 additions & 3 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ class SetAndGetParameters : public rclcpp::Node
}

// Set several different types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
auto set_parameters_results = parameters_client->set_parameters(
{
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
Expand All @@ -69,8 +70,9 @@ class SetAndGetParameters : public rclcpp::Node

std::stringstream ss;
// Get a few of the parameters just set.
for (auto & parameter : parameters_client->get_parameters({"foo", "baz",
"foobarbaz", "toto"}))
for (
auto & parameter : parameters_client->get_parameters(
{"foo", "baz", "foobarbaz", "toto"}))
{
ss << "\nParameter name: " << parameter.get_name();
ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ int main(int argc, char ** argv)
}

// Set several different types of parameters.
auto results = parameters_client->set_parameters({
auto results = parameters_client->set_parameters(
{
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
Expand Down
3 changes: 2 additions & 1 deletion demo_nodes_cpp/src/services/add_two_ints_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ class ServerNode : public rclcpp::Node
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) -> void
{
(void)request_header;
RCLCPP_INFO(this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64,
RCLCPP_INFO(
this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64,
request->a, request->b);
response->sum = request->a + request->b;
};
Expand Down
9 changes: 5 additions & 4 deletions demo_nodes_cpp/src/timers/one_off_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,11 @@ class OneOffTimerNode : public rclcpp::Node
RCLCPP_INFO(this->get_logger(), "in periodic_timer callback");
if (this->count++ % 3 == 0) {
RCLCPP_INFO(this->get_logger(), " resetting one off timer");
this->one_off_timer = this->create_wall_timer(1s, [this]() {
RCLCPP_INFO(this->get_logger(), "in one_off_timer callback");
this->one_off_timer->cancel();
});
this->one_off_timer = this->create_wall_timer(
1s, [this]() {
RCLCPP_INFO(this->get_logger(), "in one_off_timer callback");
this->one_off_timer->cancel();
});
} else {
RCLCPP_INFO(this->get_logger(), " not resetting one off timer");
}
Expand Down
3 changes: 2 additions & 1 deletion demo_nodes_cpp/src/topics/allocator_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,8 @@ int main(int argc, char ** argv)
std::list<std::string> keys = {"intra", "intraprocess", "intra-process", "intra_process"};
bool intra_process = false;

printf("This simple demo shows off a custom memory allocator to count all\n"
printf(
"This simple demo shows off a custom memory allocator to count all\n"
"instances of new/delete in the program. It can be run in either regular\n"
"mode (no arguments), or in intra-process mode (by passing 'intra' as a\n"
"command-line argument)'. It will then publish a message to the\n"
Expand Down
14 changes: 8 additions & 6 deletions image_tools/src/burger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,12 +126,14 @@ cv::Mat & Burger::render_burger(size_t width, size_t height)
}
burger_buf = cv::Scalar(0, 0, 0);
for (int b = 0; b < static_cast<int>(x.size()); b++) {
burger_template.copyTo(burger_buf(cv::Rect(
x[b],
y[b],
burger_template.size().height,
burger_template.size().width
)), burger_mask);
burger_template.copyTo(
burger_buf(
cv::Rect(
x[b],
y[b],
burger_template.size().height,
burger_template.size().width
)), burger_mask);
x[b] += x_inc[b];
y[b] += y_inc[b];
// bounce as needed
Expand Down
8 changes: 5 additions & 3 deletions lifecycle/src/lifecycle_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@ class LifecycleListener : public rclcpp::Node
: Node(node_name)
{
// Data topic from the lc_talker node
sub_data_ = this->create_subscription<std_msgs::msg::String>("lifecycle_chatter", 10,
std::bind(&LifecycleListener::data_callback, this, std::placeholders::_1));
sub_data_ = this->create_subscription<std_msgs::msg::String>(
"lifecycle_chatter", 10,
std::bind(&LifecycleListener::data_callback, this, std::placeholders::_1));

// Notification event topic. All state changes
// are published here as TransitionEvents with
Expand All @@ -57,7 +58,8 @@ class LifecycleListener : public rclcpp::Node

void notification_callback(const lifecycle_msgs::msg::TransitionEvent::SharedPtr msg)
{
RCLCPP_INFO(get_logger(), "notify callback: Transition from state %s to %s",
RCLCPP_INFO(
get_logger(), "notify callback: Transition from state %s to %s",
msg->start_state.label.c_str(), msg->goal_state.label.c_str());
}

Expand Down
8 changes: 5 additions & 3 deletions lifecycle/src/lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,8 @@ class LifecycleServiceClient : public rclcpp::Node

// We have an succesful answer. So let's print the current state.
if (future_result.get()) {
RCLCPP_INFO(get_logger(), "Node %s has current state %s.",
RCLCPP_INFO(
get_logger(), "Node %s has current state %s.",
lifecycle_node, future_result.get()->current_state.label.c_str());
return future_result.get()->current_state.id;
} else {
Expand Down Expand Up @@ -317,8 +318,9 @@ int main(int argc, char ** argv)
rclcpp::executors::SingleThreadedExecutor exe;
exe.add_node(lc_client);

std::shared_future<void> script = std::async(std::launch::async,
std::bind(callee_script, lc_client));
std::shared_future<void> script = std::async(
std::launch::async,
std::bind(callee_script, lc_client));
exe.spin_until_future_complete(script);

rclcpp::shutdown();
Expand Down
3 changes: 2 additions & 1 deletion pendulum_control/include/pendulum_control/pendulum_motor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,8 @@ class PendulumMotor
thread_param.sched_priority = 90;
pthread_attr_setschedparam(&thread_attr_, &thread_param);
pthread_attr_setschedpolicy(&thread_attr_, SCHED_RR);
pthread_create(&physics_update_thread_, &thread_attr_,
pthread_create(
&physics_update_thread_, &thread_attr_,
&pendulum_control::PendulumMotor::physics_update_wrapper, this);
}

Expand Down
3 changes: 2 additions & 1 deletion pendulum_control/src/pendulum_teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ int main(int argc, char * argv[])

double command = M_PI / 2;
if (argc < 2) {
fprintf(stderr,
fprintf(
stderr,
"Command argument not specified. Setting command to 90 degrees (PI/2 radians).\n");
} else {
command = atof(argv[1]);
Expand Down
20 changes: 12 additions & 8 deletions quality_of_service_demo/rclcpp/src/deadline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,23 +34,27 @@ static const size_t DEFAULT_PAUSE_FOR = 1000;
void print_usage()
{
printf("Usage for deadline:\n");
printf("deadline "
printf(
"deadline "
"deadline_duration "
"[%s publish_for] "
"[%s pause_for] "
"[-h]\n",
OPTION_PUBLISH_FOR,
OPTION_PAUSE_FOR);
printf("required arguments:\n");
printf("deadline_duration: "
printf(
"deadline_duration: "
"Duration in positive integer milliseconds of the Deadline QoS setting.\n");
printf("optional arguments:\n");
printf("-h : Print this help message.\n");
printf("%s publish_for : "
printf(
"%s publish_for : "
"Duration to publish (in positive integer milliseconds) until pausing the talker. "
"Defaults to %zu.\n",
OPTION_PUBLISH_FOR, DEFAULT_PUBLISH_FOR);
printf("%s pause_for : "
printf(
"%s pause_for : "
"Duration to pause (in positive integer milliseconds) before starting to publish again. "
"Defaults to %zu.\n",
OPTION_PAUSE_FOR, DEFAULT_PAUSE_FOR);
Expand Down Expand Up @@ -94,17 +98,17 @@ int main(int argc, char * argv[])
talker->get_options().event_callbacks.deadline_callback =
[node = talker.get()](rclcpp::QOSDeadlineOfferedInfo & event) -> void
{
RCLCPP_INFO(node->get_logger(),
"Offered deadline missed - total %d delta %d",
RCLCPP_INFO(
node->get_logger(), "Offered deadline missed - total %d delta %d",
event.total_count, event.total_count_change);
};

auto listener = std::make_shared<Listener>(qos_profile, topic);
listener->get_options().event_callbacks.deadline_callback =
[node = listener.get()](rclcpp::QOSDeadlineRequestedInfo & event) -> void
{
RCLCPP_INFO(node->get_logger(),
"Requested deadline missed - total %d delta %d",
RCLCPP_INFO(
node->get_logger(), "Requested deadline missed - total %d delta %d",
event.total_count, event.total_count_change);
};

Expand Down
Loading

0 comments on commit fab4fc3

Please sign in to comment.