Skip to content

Commit

Permalink
geometry_msgs/Twist to ignition::msgs::Twist (#14)
Browse files Browse the repository at this point in the history
* Adding geometry_msgs/Twist to ignition::msgs::Twist conversion.

* Fix test.
  • Loading branch information
caguero authored May 20, 2019
1 parent 586b44c commit 0665453
Show file tree
Hide file tree
Showing 12 changed files with 174 additions and 0 deletions.
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ service calls.Its support is limited to only the following message types:
| geometry_msgs/PoseStamped | ignition::msgs::Pose |
| geometry_msgs/Transform | ignition::msgs::Pose |
| geometry_msgs/TransformStamped | ignition::msgs::Pose |
| geometry_msgs/Twist | ignition::msgs::Twist |
| mav_msgs/Actuators | ignition::msgs::Actuators |
| rosgraph_msgs/Clock | ignition::msgs::Clock |
| sensor_msgs/Imu | ignition::msgs::IMU |
Expand Down
19 changes: 19 additions & 0 deletions include/ros1_ign_bridge/builtin_interfaces_factories.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Vector3.h>
#include <mav_msgs/Actuators.h>
#include <rosgraph_msgs/Clock.h>
Expand Down Expand Up @@ -259,6 +260,24 @@ Factory<
const ignition::msgs::Pose & ign_msg,
geometry_msgs::TransformStamped & ros1_msg);

template<>
void
Factory<
geometry_msgs::Twist,
ignition::msgs::Twist
>::convert_1_to_ign(
const geometry_msgs::Twist & ros1_msg,
ignition::msgs::Twist & ign_msg);

template<>
void
Factory<
geometry_msgs::Twist,
ignition::msgs::Twist
>::convert_ign_to_1(
const ignition::msgs::Twist & ign_msg,
geometry_msgs::Twist & ros1_msg);

// mav_msgs
template<>
void
Expand Down
13 changes: 13 additions & 0 deletions include/ros1_ign_bridge/convert_builtin_interfaces.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <rosgraph_msgs/Clock.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <mav_msgs/Actuators.h>
#include <sensor_msgs/FluidPressure.h>
#include <sensor_msgs/Image.h>
Expand Down Expand Up @@ -179,6 +180,18 @@ convert_ign_to_1(
const ignition::msgs::Pose & ign_msg,
geometry_msgs::TransformStamped & ros1_msg);

template<>
void
convert_1_to_ign(
const geometry_msgs::Twist & ros1_msg,
ignition::msgs::Twist & ign_msg);

template<>
void
convert_ign_to_1(
const ignition::msgs::Twist & ign_msg,
geometry_msgs::Twist & ros1_msg);

// mav_msgs
template<>
void
Expand Down
35 changes: 35 additions & 0 deletions src/builtin_interfaces_factories.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,17 @@ get_factory_builtin_interfaces(
>
>("geometry_msgs/TransformStamped", ign_type_name);
}
if (
(ros1_type_name == "geometry_msgs/Twist" || ros1_type_name == "") &&
ign_type_name == "ignition.msgs.Twist")
{
return std::make_shared<
Factory<
geometry_msgs::Twist,
ignition::msgs::Twist
>
>("geometry_msgs/Twist", ign_type_name);
}
if (
(ros1_type_name == "mav_msgs/Actuators" || ros1_type_name == "") &&
ign_type_name == "ignition.msgs.Actuators")
Expand Down Expand Up @@ -521,6 +532,30 @@ Factory<
ros1_ign_bridge::convert_ign_to_1(ign_msg, ros1_msg);
}

template<>
void
Factory<
geometry_msgs::Twist,
ignition::msgs::Twist
>::convert_1_to_ign(
const geometry_msgs::Twist & ros1_msg,
ignition::msgs::Twist & ign_msg)
{
ros1_ign_bridge::convert_1_to_ign(ros1_msg, ign_msg);
}

template<>
void
Factory<
geometry_msgs::Twist,
ignition::msgs::Twist
>::convert_ign_to_1(
const ignition::msgs::Twist & ign_msg,
geometry_msgs::Twist & ros1_msg)
{
ros1_ign_bridge::convert_ign_to_1(ign_msg, ros1_msg);
}

// mav_msgs
template<>
void
Expand Down
20 changes: 20 additions & 0 deletions src/convert_builtin_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,6 +320,26 @@ convert_ign_to_1(
}
}

template<>
void
convert_1_to_ign(
const geometry_msgs::Twist & ros1_msg,
ignition::msgs::Twist & ign_msg)
{
convert_1_to_ign(ros1_msg.linear, (*ign_msg.mutable_linear()));
convert_1_to_ign(ros1_msg.angular, (*ign_msg.mutable_angular()));
}

template<>
void
convert_ign_to_1(
const ignition::msgs::Twist & ign_msg,
geometry_msgs::Twist & ros1_msg)
{
convert_ign_to_1(ign_msg.linear(), ros1_msg.linear);
convert_ign_to_1(ign_msg.angular(), ros1_msg.angular);
}

template<>
void
convert_1_to_ign(
Expand Down
1 change: 1 addition & 0 deletions test/launch/test_ign_subscriber.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
/pose_stamped@geometry_msgs/[email protected]
/transform@geometry_msgs/[email protected]
/transform_stamped@geometry_msgs/[email protected]
/twist@geometry_msgs/[email protected]
/image@sensor_msgs/[email protected]
/imu@sensor_msgs/[email protected]
/laserscan@sensor_msgs/[email protected]
Expand Down
1 change: 1 addition & 0 deletions test/launch/test_ros1_subscriber.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
/pose_stamped@geometry_msgs/[email protected]
/transform@geometry_msgs/[email protected]
/transform_stamped@geometry_msgs/[email protected]
/twist@geometry_msgs/[email protected]
/image@sensor_msgs/[email protected]
/imu@sensor_msgs/[email protected]
/laserscan@sensor_msgs/[email protected]
Expand Down
6 changes: 6 additions & 0 deletions test/publishers/ign_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,11 @@ int main(int /*argc*/, char **/*argv*/)
ignition::msgs::Model joint_states_msg;
ros1_ign_bridge::testing::createTestMsg(joint_states_msg);

// ignition::msgs::Twist.
auto twist_pub = node.Advertise<ignition::msgs::Twist>("twist");
ignition::msgs::Twist twist_msg;
ros1_ign_bridge::testing::createTestMsg(twist_msg);

// Publish messages at 1Hz.
while (!g_terminatePub)
{
Expand All @@ -156,6 +161,7 @@ int main(int /*argc*/, char **/*argv*/)
magnetic_pub.Publish(magnetometer_msg);
actuators_pub.Publish(actuators_msg);
joint_states_pub.Publish(joint_states_msg);
twist_pub.Publish(twist_msg);

std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
Expand Down
8 changes: 8 additions & 0 deletions test/publishers/ros1_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <mav_msgs/Actuators.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/Imu.h>
Expand Down Expand Up @@ -103,6 +104,12 @@ int main(int argc, char ** argv)
geometry_msgs::TransformStamped transform_stamped_msg;
ros1_ign_bridge::testing::createTestMsg(transform_stamped_msg);

// geometry_msgs::Twist.
ros::Publisher twist_pub =
n.advertise<geometry_msgs::Twist>("twist", 1000);
geometry_msgs::Twist twist_msg;
ros1_ign_bridge::testing::createTestMsg(twist_msg);

// mav_msgs::Actuators.
ros::Publisher actuators_pub =
n.advertise<mav_msgs::Actuators>("actuators", 1000);
Expand Down Expand Up @@ -153,6 +160,7 @@ int main(int argc, char ** argv)
pose_stamped_pub.publish(pose_stamped_msg);
transform_pub.publish(transform_msg);
transform_stamped_pub.publish(transform_stamped_msg);
twist_pub.publish(twist_msg);
actuators_pub.publish(actuators_msg);
image_pub.publish(image_msg);
imu_pub.publish(imu_msg);
Expand Down
12 changes: 12 additions & 0 deletions test/subscribers/ign_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,18 @@ TEST(IgnSubscriberTest, TransformStamped)
EXPECT_TRUE(client.callbackExecuted);
}

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

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

EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(IgnSubscriberTest, Image)
{
Expand Down
13 changes: 13 additions & 0 deletions test/subscribers/ros1_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Vector3.h>
#include <mav_msgs/Actuators.h>
Expand Down Expand Up @@ -197,6 +198,18 @@ TEST(ROS1SubscriberTest, TransformStamped)
EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(ROS1SubscriberTest, Twist)
{
MyTestClass<geometry_msgs::Twist> client("twist");

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

EXPECT_TRUE(client.callbackExecuted);
}

/////////////////////////////////////////////////
TEST(ROS1SubscriberTest, Image)
{
Expand Down
45 changes: 45 additions & 0 deletions test/test_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Vector3.h>
#include <mav_msgs/Actuators.h>
Expand Down Expand Up @@ -307,6 +308,25 @@ namespace testing
EXPECT_EQ(expected_msg.child_frame_id, _msg.child_frame_id);
}

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(geometry_msgs::Twist &_msg)
{
createTestMsg(_msg.linear);
createTestMsg(_msg.angular);
}

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

compareTestMsg(_msg.linear);
compareTestMsg(_msg.angular);
}

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(mav_msgs::Actuators &_msg)
Expand Down Expand Up @@ -945,6 +965,31 @@ namespace testing
EXPECT_EQ(expected_msg.normalized(i), _msg.normalized(i));
}
}

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(ignition::msgs::Twist &_msg)
{
ignition::msgs::Header header_msg;
ignition::msgs::Vector3d linear_msg;
ignition::msgs::Vector3d angular_msg;

createTestMsg(header_msg);
createTestMsg(linear_msg);
createTestMsg(angular_msg);

_msg.mutable_header()->CopyFrom(header_msg);
_msg.mutable_linear()->CopyFrom(linear_msg);
_msg.mutable_angular()->CopyFrom(angular_msg);
}

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

Expand Down

0 comments on commit 0665453

Please sign in to comment.