Skip to content

Commit

Permalink
more demos converted
Browse files Browse the repository at this point in the history
Signed-off-by: Siddharth Kucheria <kucheria@usc.edu>
  • Loading branch information
skucheria committed Jul 18, 2019
1 parent 9c5d4ce commit 2afc9b7
Show file tree
Hide file tree
Showing 8 changed files with 370 additions and 285 deletions.
44 changes: 32 additions & 12 deletions demo_nodes_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,14 +43,10 @@ function(use_composition library folder executable)
"example_interfaces")
endfunction()
# Tutorials of Publish/Subscribe with Topics
custom_executable(topics listener)
custom_executable(topics allocator_tutorial)
custom_executable(topics listener_serialized_message)

# Tutorials of Request/Response with Services
custom_executable(services add_two_ints_client)
custom_executable(services add_two_ints_client_async)
custom_executable(services add_two_ints_server)

# Tutorials of Parameters with Asynchronous and Synchronous
custom_executable(parameters list_parameters_async)
Expand All @@ -60,32 +56,56 @@ custom_executable(parameters set_and_get_parameters_async)
custom_executable(parameters parameter_events_async)


use_composition(serverlib services add_two_ints_server)
rclcpp_components_register_node(serverlib PLUGIN "demo_nodes_cpp::ServerNode"
EXECUTABLE add_two_ints_server)
use_composition(clientasynclib services add_two_ints_client_async)
rclcpp_components_register_node(clientasynclib PLUGIN "demo_nodes_cpp::ClientNode"
EXECUTABLE add_two_ints_client_async)
use_composition(listparameterslib parameters list_parameters)
rclcpp_components_register_node(listparameterslib PLUGIN "demo_nodes_cpp::ListParameters" EXECUTABLE list_parameters)
rclcpp_components_register_node(listparameterslib PLUGIN "demo_nodes_cpp::ListParameters"
EXECUTABLE list_parameters)
use_composition(parameterblackboardlib parameters parameter_blackboard)
rclcpp_components_register_node(parameterblackboardlib PLUGIN "demo_nodes_cpp::ParameterBlackboard" EXECUTABLE parameter_blackboard)
rclcpp_components_register_node(parameterblackboardlib PLUGIN "demo_nodes_cpp::ParameterBlackboard"
EXECUTABLE parameter_blackboard)
use_composition(setandgetparameterslib parameters set_and_get_parameters)
rclcpp_components_register_node(setandgetparameterslib PLUGIN "demo_nodes_cpp::SetAndGetParameters" EXECUTABLE set_and_get_parameters)
rclcpp_components_register_node(setandgetparameterslib PLUGIN "demo_nodes_cpp::SetAndGetParameters"
EXECUTABLE set_and_get_parameters)
use_composition(talkerlib topics talker)
rclcpp_components_register_node(talkerlib PLUGIN "demo_nodes_cpp::Talker" EXECUTABLE talker)
rclcpp_components_register_node(talkerlib PLUGIN "demo_nodes_cpp::Talker"
EXECUTABLE talker)
use_composition(talkerserializedlib topics talker_serialized_message)
rclcpp_components_register_node(talkerserializedlib PLUGIN "demo_nodes_cpp::SerializedMessageTalker" EXECUTABLE talker_serialized_message)
rclcpp_components_register_node(talkerserializedlib PLUGIN "demo_nodes_cpp::SerializedMessageTalker"
EXECUTABLE talker_serialized_message)
use_composition(listenerlib topics listener)
rclcpp_components_register_node(listenerlib PLUGIN "demo_nodes_cpp::Listener"
EXECUTABLE listener)
use_composition(listenerserializedlib topics listener_serialized_message)
rclcpp_components_register_node(listenerserializedlib PLUGIN "demo_nodes_cpp::SerializedMessageListener"
EXECUTABLE listener_serialized_message)
use_composition(listenerbesteffortlib topics listener_best_effort)
rclcpp_components_register_node(listenerbesteffortlib PLUGIN "demo_nodes_cpp::ListenerBestEffort" EXECUTABLE listener_best_effort)
rclcpp_components_register_node(listenerbesteffortlib PLUGIN "demo_nodes_cpp::ListenerBestEffort"
EXECUTABLE listener_best_effort)
use_composition(oneofftimerlib timers one_off_timer)
rclcpp_components_register_node(oneofftimerlib PLUGIN "demo_nodes_cpp::OneOffTimerNode" EXECUTABLE one_off_timer)
rclcpp_components_register_node(oneofftimerlib PLUGIN "demo_nodes_cpp::OneOffTimerNode"
EXECUTABLE one_off_timer)
use_composition(resusetimerlib timers reuse_timer)
rclcpp_components_register_node(resusetimerlib PLUGIN "demo_nodes_cpp::ReuseTimerNode" EXECUTABLE reuse_timer)
rclcpp_components_register_node(resusetimerlib PLUGIN "demo_nodes_cpp::ReuseTimerNode"
EXECUTABLE reuse_timer)

install(TARGETS
talkerlib
serverlib
clientasynclib
talkerserializedlib
listenerbesteffortlib
listenerlib
oneofftimerlib
resusetimerlib
parameterblackboardlib
listparameterslib
setandgetparameterslib
listenerserializedlib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,4 +144,4 @@ int main(int argc, char ** argv)
rclcpp::shutdown();

return 0;
}
}
79 changes: 42 additions & 37 deletions demo_nodes_cpp/src/services/add_two_ints_client_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,33 +17,37 @@
#include <iostream>
#include <memory>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "rcutils/cmdline_parser.h"

#include "example_interfaces/srv/add_two_ints.hpp"

using namespace std::chrono_literals;

void print_usage()
namespace demo_nodes_cpp
{
printf("Usage for add_two_ints_client app:\n");
printf("add_two_ints_client [-s service_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-s service_name : Specify the service name for this client. Defaults to add_two_ints.\n");
}

class ClientNode : public rclcpp::Node
{
public:
explicit ClientNode(const std::string & service_name)
: Node("add_two_ints_client")
explicit ClientNode(const rclcpp::NodeOptions & options)
: Node("add_two_ints_client", options)
{
client_ = create_client<example_interfaces::srv::AddTwoInts>(service_name);

std::vector<std::string> args = options.arguments();
if (find_command_option(args, "-h")) {
print_usage();
rclcpp::shutdown();
} else {
std::string tmptopic = get_command_option(args, "-s");
if (!tmptopic.empty()) {
service_name_ = tmptopic;
}
client_ = create_client<example_interfaces::srv::AddTwoInts>(service_name_);
queue_async_request();
}
// Queue an asynchronous service request that will be sent once `spin` is called on the node.
queue_async_request();
}

void queue_async_request()
Expand Down Expand Up @@ -73,33 +77,34 @@ class ClientNode : public rclcpp::Node
auto future_result = client_->async_send_request(request, response_received_callback);
}

private:
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
};

int main(int argc, char ** argv)
{
// Force flush of the stdout buffer.
// This ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_usage();
return 0;
void print_usage()
{
printf("Usage for add_two_ints_client app:\n");
printf("add_two_ints_client [-s service_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-s service_name : Specify the service name for client. Defaults to add_two_ints.\n");
}

rclcpp::init(argc, argv);
bool find_command_option(const std::vector<std::string> & args, const std::string & option)
{
return std::find(args.begin(), args.end(), option) != args.end();
}

auto service_name = std::string("add_two_ints");
char * cli_option = rcutils_cli_get_option(argv, argv + argc, "-s");
if (nullptr != cli_option) {
service_name = std::string(cli_option);
std::string get_command_option(const std::vector<std::string> & args, const std::string & option)
{
auto it = std::find(args.begin(), args.end(), option);
if (it != args.end() && ++it != args.end()) {
return *it;
}
return std::string();
}

auto node = std::make_shared<ClientNode>(service_name);
rclcpp::spin(node);
private:
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
std::string service_name_ = "add_two_ints";
};

} // namespace demo_nodes_cpp

rclcpp::shutdown();
return 0;
}
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::ClientNode)
84 changes: 47 additions & 37 deletions demo_nodes_cpp/src/services/add_two_ints_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,29 +16,48 @@
#include <cstdio>
#include <memory>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "rcutils/cmdline_parser.h"

#include "example_interfaces/srv/add_two_ints.hpp"

void print_usage()
namespace demo_nodes_cpp
{
printf("Usage for add_two_ints_server app:\n");
printf("add_two_ints_server [-s service_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function.\n");
printf("-s service_name : Specify the service name for this server. Defaults to add_two_ints.\n");
}


class ServerNode : public rclcpp::Node
{
public:
explicit ServerNode(const std::string & service_name)
: Node("add_two_ints_server")
explicit ServerNode(const rclcpp::NodeOptions & options)
: Node("add_two_ints_server", options)
{
std::vector<std::string> args = options.arguments();
if (find_command_option(args, "-h")) {
print_usage();
rclcpp::shutdown();
} else {
std::string tmptopic = get_command_option(args, "-s");
if (!tmptopic.empty()) {
service_name_ = tmptopic;
}
execute();
}
// Create a callback function for when service requests are received.
}

void print_usage()
{
printf("Uage for add_two_ints_server app:\n");
printf("add_two_ints_server [-s service_name] [-h]\n");
printf("options:\n");
printf("-h : Print this help function\n");
printf("-s service_name : Specify the service name for this sever. Defaults to add_two_ints\n");
}

void execute()
{
auto handle_add_two_ints =
[this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
Expand All @@ -49,38 +68,29 @@ class ServerNode : public rclcpp::Node
request->a, request->b);
response->sum = request->a + request->b;
};

// Create a service that will use the callback function to handle requests.
srv_ = create_service<example_interfaces::srv::AddTwoInts>(service_name, handle_add_two_ints);
srv_ = create_service<example_interfaces::srv::AddTwoInts>(service_name_, handle_add_two_ints);
}

private:
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr srv_;
};

int main(int argc, char * argv[])
{
// Force flush of the stdout buffer.
// This ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_usage();
return 0;
bool find_command_option(const std::vector<std::string> & args, const std::string & option)
{
return std::find(args.begin(), args.end(), option) != args.end();
}

rclcpp::init(argc, argv);

auto service_name = std::string("add_two_ints");
char * cli_option = rcutils_cli_get_option(argv, argv + argc, "-s");
if (nullptr != cli_option) {
service_name = std::string(cli_option);
std::string get_command_option(const std::vector<std::string> & args, const std::string & option)
{
auto it = std::find(args.begin(), args.end(), option);
if (it != args.end() && ++it != args.end()) {
return *it;
}
return std::string();
}

auto node = std::make_shared<ServerNode>(service_name);
rclcpp::spin(node);
private:
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr srv_;
std::string service_name_ = "add_two_ints";
};

} // namespace demo_nodes_cpp

rclcpp::shutdown();
return 0;
}
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::ServerNode)
Loading

0 comments on commit 2afc9b7

Please sign in to comment.