Skip to content

Commit

Permalink
more changes
Browse files Browse the repository at this point in the history
  • Loading branch information
skucheria committed Jul 16, 2019
1 parent 8384239 commit 2761ed7
Show file tree
Hide file tree
Showing 3 changed files with 63 additions and 66 deletions.
17 changes: 7 additions & 10 deletions demo_nodes_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,8 @@ function(use_composition library folder executable)
"example_interfaces")
endfunction()
# Tutorials of Publish/Subscribe with Topics
#custom_executable(topics talker)
custom_executable(topics listener)
custom_executable(topics listener_best_effort)
custom_executable(topics allocator_tutorial)
#custom_executable(topics talker_serialized_message)
custom_executable(topics listener_serialized_message)

# Tutorials of Request/Response with Services
Expand All @@ -56,27 +53,25 @@ 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)
custom_executable(parameters list_parameters_async)
#custom_executable(parameters parameter_blackboard)
custom_executable(parameters parameter_events)
custom_executable(parameters parameter_events_async)
custom_executable(parameters even_parameters_node)
custom_executable(parameters set_and_get_parameters)
custom_executable(parameters set_and_get_parameters_async)
custom_executable(parameters parameter_events_async)

# Tutorials of Timers
#custom_executable(timers one_off_timer)
#custom_executable(timers reuse_timer)

use_composition(listparameterslib parameters 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)
use_composition(setandgetparameterslib parameters 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)
use_composition(talkerserializedlib topics talker_serialized_message)
rclcpp_components_register_node(talkerserializedlib PLUGIN "demo_nodes_cpp::SerializedMessageTalker" EXECUTABLE talker_serialized_message)
use_composition(listenerbesteffortlib topics 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)
use_composition(resusetimerlib timers reuse_timer)
Expand All @@ -85,10 +80,12 @@ rclcpp_components_register_node(resusetimerlib PLUGIN "demo_nodes_cpp::ReuseTime
install(TARGETS
talkerlib
talkerserializedlib
listenerbesteffortlib
oneofftimerlib
resusetimerlib
parameterblackboardlib
listparameterslib
setandgetparameterslib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
Expand Down
93 changes: 49 additions & 44 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,61 +17,66 @@
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"

using namespace std::chrono_literals;

int main(int argc, char ** argv)
namespace demo_nodes_cpp
{
// Force flush of the stdout buffer.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

rclcpp::init(argc, argv);

auto node = rclcpp::Node::make_shared("set_and_get_parameters");
class SetAndGetParameters : public rclcpp::Node
{
public:
explicit SetAndGetParameters(const rclcpp::NodeOptions & options)
: Node("set_and_get_parameters", options)
{
this->declare_parameter("foo");
this->declare_parameter("bar");
this->declare_parameter("baz");
this->declare_parameter("foobar");
this->declare_parameter("foobarbaz");
this->declare_parameter("toto");

// Declare parameters that may be set on this node
node->declare_parameter("foo");
node->declare_parameter("bar");
node->declare_parameter("baz");
node->declare_parameter("foobar");
node->declare_parameter("foobarbaz");
node->declare_parameter("toto");
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(this);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
rclcpp::shutdown();
}
RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
}

auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
return 0;
// Set several different types of 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),
rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
});
// Check to see if they were set.
for (auto & result : set_parameters_results) {
if (!result.successful) {
RCLCPP_ERROR(this->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
}
}
RCLCPP_INFO(node->get_logger(), "service not available, waiting again...");
}

// Set several different types of 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),
rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
});
// Check to see if they were set.
for (auto & result : set_parameters_results) {
if (!result.successful) {
RCLCPP_ERROR(node->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
std::stringstream ss;
// Get a few of the parameters just set.
for (auto & parameter : parameters_client->get_parameters({"foo", "baz",
"foobarbaz", "toto"}))
{
ss << "\nParameter name: " << parameter.get_name();
ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
parameter.value_to_string();
}
}
RCLCPP_INFO(this->get_logger(), ss.str().c_str());

std::stringstream ss;
// Get a few of the parameters just set.
for (auto & parameter : parameters_client->get_parameters({"foo", "baz", "foobarbaz", "toto"})) {
ss << "\nParameter name: " << parameter.get_name();
ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
parameter.value_to_string();
rclcpp::shutdown();
}
RCLCPP_INFO(node->get_logger(), ss.str().c_str());
};

rclcpp::shutdown();
} // namespace demo_nodes_cpp

return 0;
}
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::SetAndGetParameters)
19 changes: 7 additions & 12 deletions demo_nodes_cpp/src/topics/listener_best_effort.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,16 @@
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "std_msgs/msg/string.hpp"

namespace demo_nodes_cpp
{
class ListenerBestEffort : public rclcpp::Node
{
public:
ListenerBestEffort()
: Node("listener")
explicit ListenerBestEffort(const rclcpp::NodeOptions & options)
: Node("listener", options)
{
auto callback =
[this](const typename std_msgs::msg::String::SharedPtr msg) -> void
Expand All @@ -37,14 +40,6 @@ class ListenerBestEffort : public rclcpp::Node
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
};

int main(int argc, char * argv[])
{
// Force flush of the stdout buffer.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
} // namespace demo_nodes_cpp

rclcpp::init(argc, argv);
auto node = std::make_shared<ListenerBestEffort>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::ListenerBestEffort)

0 comments on commit 2761ed7

Please sign in to comment.