Skip to content

Commit

Permalink
Merge pull request #31 from ros2/update_message_api
Browse files Browse the repository at this point in the history
update message API
  • Loading branch information
dirk-thomas committed Jun 17, 2015
2 parents 170450c + f822161 commit 1c9c1c7
Show file tree
Hide file tree
Showing 15 changed files with 48 additions and 48 deletions.
4 changes: 2 additions & 2 deletions userland/src/explicit/two_nodes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@

#include <simple_msgs/msg/string.hpp>

void on_message(const simple_msgs::msg::String::ConstPtr & msg)
void on_message(const simple_msgs::msg::String::ConstSharedPtr & msg)
{
std::cout << "I heard [" << msg->data << "]" << std::endl;
}

void on_timer(rclcpp::Publisher::SharedPtr & publisher, int & i)
{
simple_msgs::msg::String::Ptr msg(new simple_msgs::msg::String());
simple_msgs::msg::String::SharedPtr msg(new simple_msgs::msg::String());
msg->data = "Hello World: " + std::to_string(i++);
if (publisher) {
std::cout << "Publishing: '" << msg->data << "'" << std::endl;
Expand Down
8 changes: 4 additions & 4 deletions userland/src/imu/imu32/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@


template<typename T>
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t))
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t))
{
auto p = node->create_publisher<T>("imu", 1000);
typename T::Ptr ros_msg(new T());
typename T::SharedPtr ros_msg(new T());

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate rate(10);
Expand All @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr
return 0;
}

void set_imu_data(simple_msgs::msg::Imu32::Ptr & ros_msg, size_t i)
void set_imu_data(simple_msgs::msg::Imu32::SharedPtr & ros_msg, size_t i)
{
// Define the header
ros_msg->header.seq = i;
Expand Down Expand Up @@ -88,7 +88,7 @@ void set_imu_data(simple_msgs::msg::Imu32::Ptr & ros_msg, size_t i)
}

template<typename T>
void set_empty(typename T::Ptr & ros_msg, size_t i)
void set_empty(typename T::SharedPtr & ros_msg, size_t i)
{
ros_msg.reset(new T());
}
Expand Down
2 changes: 1 addition & 1 deletion userland/src/imu/imu32/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
return sub;
}

void print_accel_data(const simple_msgs::msg::Imu32::ConstPtr & msg)
void print_accel_data(const simple_msgs::msg::Imu32::ConstSharedPtr & msg)
{

std::cout << "-------------------------" << std::endl;
Expand Down
8 changes: 4 additions & 4 deletions userland/src/imu/imu_double/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@


template<typename T>
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t))
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t))
{
auto p = node->create_publisher<T>("imu", 1000);
typename T::Ptr ros_msg(new T());
typename T::SharedPtr ros_msg(new T());

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate rate(10);
Expand All @@ -48,15 +48,15 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr
return 0;
}

void set_accel_data(simple_msgs::msg::Vector3::Ptr & ros_msg, size_t i)
void set_accel_data(simple_msgs::msg::Vector3::SharedPtr & ros_msg, size_t i)
{
ros_msg->x = 1;
ros_msg->y = 2;
ros_msg->z = 3;
}

template<typename T>
void set_empty(typename T::Ptr & ros_msg, size_t i)
void set_empty(typename T::SharedPtr & ros_msg, size_t i)
{
ros_msg.reset(new T());
}
Expand Down
2 changes: 1 addition & 1 deletion userland/src/imu/imu_double/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
return sub;
}

void print_accel_data(const simple_msgs::msg::Vector3::ConstPtr & msg)
void print_accel_data(const simple_msgs::msg::Vector3::ConstSharedPtr & msg)
{
std::cout << "-------------------------" << std::endl;
std::cout << "Got accel x=" << msg->x << std::endl;
Expand Down
8 changes: 4 additions & 4 deletions userland/src/imu/imu_float/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@


template<typename T>
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t))
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t))
{
auto p = node->create_publisher<T>("imu", 1000);
typename T::Ptr ros_msg(new T());
typename T::SharedPtr ros_msg(new T());

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate rate(10);
Expand All @@ -48,15 +48,15 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr
return 0;
}

void set_accel_data(simple_msgs::msg::Vector3Float::Ptr & ros_msg, size_t i)
void set_accel_data(simple_msgs::msg::Vector3Float::SharedPtr & ros_msg, size_t i)
{
ros_msg->x = 1;
ros_msg->y = 2;
ros_msg->z = 3;
}

template<typename T>
void set_empty(typename T::Ptr & ros_msg, size_t i)
void set_empty(typename T::SharedPtr & ros_msg, size_t i)
{
ros_msg.reset(new T());
}
Expand Down
2 changes: 1 addition & 1 deletion userland/src/imu/imu_float/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
return sub;
}

void print_accel_data(const simple_msgs::msg::Vector3Float::ConstPtr & msg)
void print_accel_data(const simple_msgs::msg::Vector3Float::ConstSharedPtr & msg)
{
std::cout << "-------------------------" << std::endl;
std::cout << "Got accel x=" << msg->x << std::endl;
Expand Down
8 changes: 4 additions & 4 deletions userland/src/imu/imu_int/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@


template<typename T>
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t))
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t))
{
auto p = node->create_publisher<T>("imu", 1000);
typename T::Ptr ros_msg(new T());
typename T::SharedPtr ros_msg(new T());

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate rate(10);
Expand All @@ -48,15 +48,15 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr
return 0;
}

void set_accel_data(simple_msgs::msg::Vector3Int::Ptr & ros_msg, size_t i)
void set_accel_data(simple_msgs::msg::Vector3Int::SharedPtr & ros_msg, size_t i)
{
ros_msg->x = 1;
ros_msg->y = 2;
ros_msg->z = 3;
}

template<typename T>
void set_empty(typename T::Ptr & ros_msg, size_t i)
void set_empty(typename T::SharedPtr & ros_msg, size_t i)
{
ros_msg.reset(new T());
}
Expand Down
2 changes: 1 addition & 1 deletion userland/src/imu/imu_int/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
return sub;
}

void print_accel_data(const simple_msgs::msg::Vector3Int::ConstPtr & msg)
void print_accel_data(const simple_msgs::msg::Vector3Int::ConstSharedPtr & msg)
{
std::cout << "-------------------------" << std::endl;
std::cout << "Got accel x=" << msg->x << std::endl;
Expand Down
8 changes: 4 additions & 4 deletions userland/src/imu/rosimu/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@


template<typename T>
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t))
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t))
{
auto p = node->create_publisher<T>("imu", 1000);
typename T::Ptr ros_msg(new T());
typename T::SharedPtr ros_msg(new T());

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate rate(10);
Expand All @@ -48,7 +48,7 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr
return 0;
}

void set_imu_data(simple_msgs::msg::Imu::Ptr & ros_msg, size_t i)
void set_imu_data(simple_msgs::msg::Imu::SharedPtr & ros_msg, size_t i)
{
// Define the header
ros_msg->header.seq = i;
Expand Down Expand Up @@ -88,7 +88,7 @@ void set_imu_data(simple_msgs::msg::Imu::Ptr & ros_msg, size_t i)
}

template<typename T>
void set_empty(typename T::Ptr & ros_msg, size_t i)
void set_empty(typename T::SharedPtr & ros_msg, size_t i)
{
ros_msg.reset(new T());
}
Expand Down
2 changes: 1 addition & 1 deletion userland/src/imu/rosimu/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
return sub;
}

void print_accel_data(const simple_msgs::msg::Imu::ConstPtr & msg)
void print_accel_data(const simple_msgs::msg::Imu::ConstSharedPtr & msg)
{

std::cout << "-------------------------" << std::endl;
Expand Down
4 changes: 2 additions & 2 deletions userland/src/prototype_intraprocesses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ void decrement(Intraprocess_t * meta)
}
}

void callback(const simple_msgs::msg::Intraprocess::ConstPtr & msg)
void callback(const simple_msgs::msg::Intraprocess::ConstSharedPtr & msg)
{
Intraprocess_t * meta = (Intraprocess_t *) msg->ptr;
std::cout << "------ Got message: " << *(meta->data) << std::endl;
Expand Down Expand Up @@ -65,7 +65,7 @@ void launch_publisher(Intraprocess_t * s)
std::cout << "------ Creating publisher:" << std::endl;
auto n = rclcpp::Node::make_shared("prototype_intraprocess_pub");
auto p = n->create_publisher<simple_msgs::msg::Intraprocess>("intraprocess", 1000);
simple_msgs::msg::Intraprocess::Ptr ros_msg;
simple_msgs::msg::Intraprocess::SharedPtr ros_msg;

// Wait one second for the publisher to set up.
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
Expand Down
20 changes: 10 additions & 10 deletions userland/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,10 @@


template<typename T>
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr &, size_t))
int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::SharedPtr &, size_t))
{
auto p = node->create_publisher<T>("topic_name", 1000);
typename T::Ptr ros_msg(new T());
typename T::SharedPtr ros_msg(new T());

auto start = std::chrono::steady_clock::now();
rclcpp::WallRate rate(10);
Expand All @@ -56,12 +56,12 @@ int publish(rclcpp::Node::SharedPtr node, void (* set_data_func)(typename T::Ptr
return 0;
}

void set_counter_data(simple_msgs::msg::Uint32::Ptr & ros_msg, size_t i)
void set_counter_data(simple_msgs::msg::Uint32::SharedPtr & ros_msg, size_t i)
{
ros_msg->data = i;
}

void set_all_primitive_data(simple_msgs::msg::AllPrimitiveTypes::Ptr & ros_msg, size_t i)
void set_all_primitive_data(simple_msgs::msg::AllPrimitiveTypes::SharedPtr & ros_msg, size_t i)
{
ros_msg->my_bool = i % 2;
ros_msg->my_byte = i % 256;
Expand All @@ -79,7 +79,7 @@ void set_all_primitive_data(simple_msgs::msg::AllPrimitiveTypes::Ptr & ros_msg,
ros_msg->my_string = "foo " + std::to_string(i);
}

void set_all_static_array(simple_msgs::msg::AllStaticArrayTypes::Ptr & ros_msg, size_t i)
void set_all_static_array(simple_msgs::msg::AllStaticArrayTypes::SharedPtr & ros_msg, size_t i)
{
int start = i - 1; // get the zero
int end = i + 5; // assuming that the array size is 6
Expand All @@ -103,7 +103,7 @@ void set_all_static_array(simple_msgs::msg::AllStaticArrayTypes::Ptr & ros_msg,
}
}

void set_all_dynamic_array(simple_msgs::msg::AllDynamicArrayTypes::Ptr & ros_msg, size_t i)
void set_all_dynamic_array(simple_msgs::msg::AllDynamicArrayTypes::SharedPtr & ros_msg, size_t i)
{
int array_size = i - 1;
ros_msg->my_bool.resize(array_size);
Expand Down Expand Up @@ -139,12 +139,12 @@ void set_all_dynamic_array(simple_msgs::msg::AllDynamicArrayTypes::Ptr & ros_msg
}
}

void set_nested(simple_msgs::msg::Nested::Ptr & ros_msg, size_t i)
void set_nested(simple_msgs::msg::Nested::SharedPtr & ros_msg, size_t i)
{
ros_msg->submsg.data = i;
}

void set_string(simple_msgs::msg::String::Ptr & ros_msg, size_t i)
void set_string(simple_msgs::msg::String::SharedPtr & ros_msg, size_t i)
{
i = std::pow(2, i) - 1;
ros_msg->data = "";
Expand All @@ -154,12 +154,12 @@ void set_string(simple_msgs::msg::String::Ptr & ros_msg, size_t i)
}

template<typename T>
void set_empty(typename T::Ptr & ros_msg, size_t i)
void set_empty(typename T::SharedPtr & ros_msg, size_t i)
{
ros_msg.reset(new T());
}

void set_builtin(simple_msgs::msg::AllBuiltinTypes::Ptr & ros_msg, size_t i)
void set_builtin(simple_msgs::msg::AllBuiltinTypes::SharedPtr & ros_msg, size_t i)
{
ros_msg->my_duration.sec = -i;
ros_msg->my_duration.nanosec = i;
Expand Down
4 changes: 2 additions & 2 deletions userland/src/ros1_like/listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@
// #include "std_msgs/String.h"
#include <simple_msgs/msg/string.hpp>

// void chatterCallback(const std_msgs::String::ConstPtr& msg)
void chatterCallback(const simple_msgs::msg::String::ConstPtr & msg)
// void chatterCallback(const std_msgs::String::ConstSharedPtr& msg)
void chatterCallback(const simple_msgs::msg::String::ConstSharedPtr & msg)
{
// ROS_INFO("I heard: [%s]", msg->data.c_str());
std::cout << "I heard: [" << msg->data << "]" << std::endl;
Expand Down
14 changes: 7 additions & 7 deletions userland/src/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,12 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
return sub;
}

void print_counter_data(const simple_msgs::msg::Uint32::ConstPtr & msg)
void print_counter_data(const simple_msgs::msg::Uint32::ConstSharedPtr & msg)
{
std::cout << "Got message #" << msg->data << std::endl;
}

void print_all_primitive_data(const simple_msgs::msg::AllPrimitiveTypes::ConstPtr & msg)
void print_all_primitive_data(const simple_msgs::msg::AllPrimitiveTypes::ConstSharedPtr & msg)
{
std::cout << "Got message:" << std::endl;
std::cout << " my_bool: " << msg->my_bool << std::endl;
Expand All @@ -67,7 +67,7 @@ void print_all_primitive_data(const simple_msgs::msg::AllPrimitiveTypes::ConstPt
} \
std::cout << std::endl;

void print_all_static_array(const simple_msgs::msg::AllStaticArrayTypes::ConstPtr & msg)
void print_all_static_array(const simple_msgs::msg::AllStaticArrayTypes::ConstSharedPtr & msg)
{
std::cout << "Got message:" << std::endl;
PRINT_STATIC_ARRAY_FIELD(my_bool, 6)
Expand All @@ -93,7 +93,7 @@ void print_all_static_array(const simple_msgs::msg::AllStaticArrayTypes::ConstPt
} \
std::cout << std::endl;

void print_all_dynamic_array(const simple_msgs::msg::AllDynamicArrayTypes::ConstPtr & msg)
void print_all_dynamic_array(const simple_msgs::msg::AllDynamicArrayTypes::ConstSharedPtr & msg)
{
std::cout << "Got message:" << std::endl;
PRINT_DYNAMIC_ARRAY_FIELD(my_bool)
Expand All @@ -112,17 +112,17 @@ void print_all_dynamic_array(const simple_msgs::msg::AllDynamicArrayTypes::Const
PRINT_DYNAMIC_ARRAY_FIELD(my_string)
}

void print_nested(const simple_msgs::msg::Nested::ConstPtr & msg)
void print_nested(const simple_msgs::msg::Nested::ConstSharedPtr & msg)
{
std::cout << "Got message #" << msg->submsg.data << std::endl;
}

void print_string(const simple_msgs::msg::String::ConstPtr & msg)
void print_string(const simple_msgs::msg::String::ConstSharedPtr & msg)
{
std::cout << "Got message: " << msg->data << std::endl;
}

void print_builtin(const simple_msgs::msg::AllBuiltinTypes::ConstPtr & msg)
void print_builtin(const simple_msgs::msg::AllBuiltinTypes::ConstSharedPtr & msg)
{
std::cout << "Got message: " << msg->my_duration.sec
<< ":" << msg->my_duration.nanosec
Expand Down

0 comments on commit 1c9c1c7

Please sign in to comment.