Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add support for std_msgs/Empty #53

Merged
merged 1 commit into from Nov 22, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions ros_ign_bridge/README.md
Expand Up @@ -9,6 +9,7 @@ service calls. Its support is limited to only the following message types:
| ROS type | Ignition Transport type |
|--------------------------------|:--------------------------------:|
| std_msgs/Bool | ignition::msgs::Boolean |
| std_msgs/Empty | ignition::msgs::Empty |
| std_msgs/Float32 | ignition::msgs::Float |
| std_msgs/Header | ignition::msgs::Header |
| std_msgs/String | ignition::msgs::StringMsg |
Expand Down
Expand Up @@ -35,6 +35,7 @@
#include <sensor_msgs/msg/magnetic_field.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/bool.hpp>
#include <std_msgs/msg/empty.hpp>
#include <std_msgs/msg/float32.hpp>
#include <std_msgs/msg/string.hpp>

Expand Down Expand Up @@ -80,6 +81,24 @@ Factory<
const ignition::msgs::Boolean & ign_msg,
std_msgs::msg::Bool & ros_msg);

template<>
void
Factory<
std_msgs::msg::Empty,
ignition::msgs::Empty
>::convert_ros_to_ign(
const std_msgs::msg::Empty & ros_msg,
ignition::msgs::Empty & ign_msg);

template<>
void
Factory<
std_msgs::msg::Empty,
ignition::msgs::Empty
>::convert_ign_to_ros(
const ignition::msgs::Empty & ign_msg,
std_msgs::msg::Empty & ros_msg);

template<>
void
Factory<
Expand Down
Expand Up @@ -37,6 +37,7 @@
#include <sensor_msgs/msg/magnetic_field.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/bool.hpp>
#include <std_msgs/msg/empty.hpp>
#include <std_msgs/msg/float32.hpp>
#include <std_msgs/msg/string.hpp>

Expand All @@ -61,6 +62,18 @@ convert_ign_to_ros(
const ignition::msgs::Boolean & ign_msg,
std_msgs::msg::Bool & ros_msg);

template<>
void
convert_ros_to_ign(
const std_msgs::msg::Empty & ros_msg,
ignition::msgs::Empty & ign_msg);

template<>
void
convert_ign_to_ros(
const ignition::msgs::Empty & ign_msg,
std_msgs::msg::Empty & ros_msg);

template<>
void
convert_ros_to_ign(
Expand Down
34 changes: 34 additions & 0 deletions ros_ign_bridge/src/builtin_interfaces_factories.cpp
Expand Up @@ -38,6 +38,16 @@ get_factory_builtin_interfaces(
>
>("std_msgs/msg/Bool", ign_type_name);
}
if ((ros_type_name == "std_msgs/msg/Empty" || ros_type_name.empty()) &&
ign_type_name == "ignition.msgs.Empty")
{
return std::make_shared<
Factory<
std_msgs::msg::Empty,
ignition::msgs::Empty
>
>("std_msgs/msg/Empty", ign_type_name);
}
if ((ros_type_name == "std_msgs/msg/Float32" || ros_type_name.empty()) &&
ign_type_name == "ignition.msgs.Float")
{
Expand Down Expand Up @@ -314,6 +324,30 @@ Factory<
ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
}

template<>
void
Factory<
std_msgs::msg::Empty,
ignition::msgs::Empty
>::convert_ros_to_ign(
const std_msgs::msg::Empty & ros_msg,
ignition::msgs::Empty & ign_msg)
{
ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
}

template<>
void
Factory<
std_msgs::msg::Empty,
ignition::msgs::Empty
>::convert_ign_to_ros(
const ignition::msgs::Empty & ign_msg,
std_msgs::msg::Empty & ros_msg)
{
ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
}

template<>
void
Factory<
Expand Down
16 changes: 16 additions & 0 deletions ros_ign_bridge/src/convert_builtin_interfaces.cpp
Expand Up @@ -68,6 +68,22 @@ convert_ign_to_ros(
ros_msg.data = ign_msg.data();
}

template<>
void
convert_ros_to_ign(
const std_msgs::msg::Empty &,
ignition::msgs::Empty &)
{
}

template<>
void
convert_ign_to_ros(
const ignition::msgs::Empty &,
std_msgs::msg::Empty &)
{
}

template<>
void
convert_ros_to_ign(
Expand Down
4 changes: 3 additions & 1 deletion ros_ign_bridge/test/launch/test_ign_subscriber.launch
Expand Up @@ -3,7 +3,9 @@
<!-- Launch the bridge -->
<node name="parameter_bridge_ign_subscriber" pkg="ros_ign_bridge"
type="parameter_bridge"
args="/float@std_msgs/Float32@ignition.msgs.Float
args="/bool@std_msgs/Bool@ignition.msgs.Boolean
/empty@std_msgs/Empty@ignition.msgs.Empty
/float@std_msgs/Float32@ignition.msgs.Float
/header@std_msgs/Header@ignition.msgs.Header
/string@std_msgs/String@ignition.msgs.StringMsg
/quaternion@geometry_msgs/Quaternion@ignition.msgs.Quaternion
Expand Down
4 changes: 3 additions & 1 deletion ros_ign_bridge/test/launch/test_ros_subscriber.launch
Expand Up @@ -3,7 +3,9 @@
<!-- Launch the bridge -->
<node name="parameter_bridge_ros_subscriber" pkg="ros_ign_bridge"
type="parameter_bridge"
args="/float@std_msgs/Float32@ignition.msgs.Float
args="/bool@std_msgs/Bool@ignition.msgs.Boolean
/empty@std_msgs/Empty@ignition.msgs.Empty
/float@std_msgs/Float32@ignition.msgs.Float
/header@std_msgs/Header@ignition.msgs.Header
/string@std_msgs/String@ignition.msgs.StringMsg
/quaternion@geometry_msgs/Quaternion@ignition.msgs.Quaternion
Expand Down
11 changes: 11 additions & 0 deletions ros_ign_bridge/test/publishers/ign_publisher.cpp
Expand Up @@ -48,6 +48,15 @@ int main(int /*argc*/, char **/*argv*/)
// Create a transport node and advertise a topic.
ignition::transport::Node node;

// ignition::msgs::Boolean.
auto bool_pub = node.Advertise<ignition::msgs::Boolean>("bool");
ignition::msgs::Boolean bool_msg;
ros_ign_bridge::testing::createTestMsg(bool_msg);

// ignition::msgs::Empty.
auto empty_pub = node.Advertise<ignition::msgs::Empty>("empty");
ignition::msgs::Empty empty_msg;

// ignition::msgs::Float.
auto float_pub = node.Advertise<ignition::msgs::Float>("float");
ignition::msgs::Float float_msg;
Expand Down Expand Up @@ -170,6 +179,8 @@ int main(int /*argc*/, char **/*argv*/)
// Publish messages at 1Hz.
while (!g_terminatePub)
{
bool_pub.Publish(bool_msg);
empty_pub.Publish(empty_msg);
float_pub.Publish(float_msg);
header_pub.Publish(header_msg);
string_pub.Publish(string_msg);
Expand Down
12 changes: 12 additions & 0 deletions ros_ign_bridge/test/publishers/ros_publisher.cpp
Expand Up @@ -15,6 +15,7 @@
#include <thread>

#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Header.h>
#include <std_msgs/String.h>
Expand Down Expand Up @@ -46,6 +47,15 @@ int main(int argc, char ** argv)
ros::NodeHandle n;
ros::Rate loop_rate(1);

// std_msgs::Bool.
ros::Publisher bool_pub = n.advertise<std_msgs::Bool>("bool", 1000);
std_msgs::Bool bool_msg;
ros_ign_bridge::testing::createTestMsg(bool_msg);

// std_msgs::Empty.
ros::Publisher empty_pub = n.advertise<std_msgs::Empty>("empty", 1000);
std_msgs::Empty empty_msg;

// std_msgs::Float32.
ros::Publisher float_pub = n.advertise<std_msgs::Float32>("float", 1000);
std_msgs::Float32 float_msg;
Expand Down Expand Up @@ -184,6 +194,8 @@ int main(int argc, char ** argv)
while (ros::ok())
{
// Publish all messages.
bool_pub.publish(bool_msg);
empty_pub.publish(empty_msg);
float_pub.publish(float_msg);
header_pub.publish(header_msg);
string_pub.publish(string_msg);
Expand Down
24 changes: 24 additions & 0 deletions ros_ign_bridge/test/subscribers/ign_subscriber.cpp
Expand Up @@ -47,6 +47,30 @@ class MyTestClass
private: ignition::transport::Node node;
};

/////////////////////////////////////////////////
TEST(IgnSubscriberTest, Boolean)
{
MyTestClass<ignition::msgs::Boolean> client("bool");

using namespace std::chrono_literals;
ros_ign_bridge::testing::waitUntilBoolVar(
client.callbackExecuted, 10ms, 200);

EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(IgnSubscriberTest, Empty)
{
MyTestClass<ignition::msgs::Empty> client("empty");

using namespace std::chrono_literals;
ros_ign_bridge::testing::waitUntilBoolVar(
client.callbackExecuted, 10ms, 200);

EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(IgnSubscriberTest, Float)
{
Expand Down
25 changes: 25 additions & 0 deletions ros_ign_bridge/test/subscribers/ros_subscriber.cpp
Expand Up @@ -17,6 +17,7 @@

#include <gtest/gtest.h>
#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Header.h>
#include <std_msgs/String.h>
Expand Down Expand Up @@ -70,6 +71,30 @@ class MyTestClass
private: ros::Subscriber sub;
};

/////////////////////////////////////////////////
TEST(ROSSubscriberTest, Bool)
{
MyTestClass<std_msgs::Bool> client("bool");

using namespace std::chrono_literals;
ros_ign_bridge::testing::waitUntilBoolVarAndSpin(
client.callbackExecuted, 10ms, 200);

EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(ROSSubscriberTest, Empty)
{
MyTestClass<std_msgs::Empty> client("empty");

using namespace std::chrono_literals;
ros_ign_bridge::testing::waitUntilBoolVarAndSpin(
client.callbackExecuted, 10ms, 200);

EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(ROSSubscriberTest, Float)
{
Expand Down
48 changes: 48 additions & 0 deletions ros_ign_bridge/test/test_utils.h
Expand Up @@ -20,6 +20,8 @@

#include <gtest/gtest.h>
#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Header.h>
#include <std_msgs/String.h>
Expand Down Expand Up @@ -104,6 +106,29 @@ namespace testing
/// ROS test utils
//////////////////////////////////////////////////

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(std_msgs::Bool &_msg)
{
_msg.data = true;
}

/// \brief Compare a message with the populated for testing.
/// \param[in] _msg The message to compare.
void compareTestMsg(const std_msgs::Bool &_msg)
{
std_msgs::Bool expected_msg;
createTestMsg(expected_msg);

EXPECT_EQ(expected_msg.data, _msg.data);
}

/// \brief Compare a message with the populated for testing. Noop for Empty
/// \param[in] _msg The message to compare.
void compareTestMsg(const std_msgs::Empty &)
{
}

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(std_msgs::Float32 &_msg)
Expand Down Expand Up @@ -772,6 +797,29 @@ namespace testing
/// Ignition::msgs test utils
//////////////////////////////////////////////////

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(ignition::msgs::Boolean &_msg)
{
_msg.set_data(true);
}

/// \brief Compare a message with the populated for testing.
/// \param[in] _msg The message to compare.
void compareTestMsg(const ignition::msgs::Boolean &_msg)
{
ignition::msgs::Boolean expected_msg;
createTestMsg(expected_msg);

EXPECT_EQ(expected_msg.data(), _msg.data());
}

/// \brief Compare a message with the populated for testing. Noop for Empty
/// \param[in] _msg The message to compare.
void compareTestMsg(const ignition::msgs::Empty &)
{
}

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(ignition::msgs::Float &_msg)
Expand Down