measure time static vs. dynamic

This commit is contained in:
Dirk Thomas 2014-08-04 12:09:47 -07:00
parent 97322affd2
commit 277d676aa2
4 changed files with 54 additions and 23 deletions

View file

@ -36,7 +36,7 @@ void register_type__@(spec.base_type.type)(DDSDomainParticipant * participant, c
void convert_ros_message_to_dds__@(spec.base_type.type)(const void * untyped_ros_message, @(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_& dds_message)
{
std::cout << " @(spec.base_type.pkg_name)::type_support::convert_ros_message_to_dds__@(spec.base_type.type)()" << std::endl;
//std::cout << " @(spec.base_type.pkg_name)::type_support::convert_ros_message_to_dds__@(spec.base_type.type)()" << std::endl;
const @(spec.base_type.pkg_name)::@(spec.base_type.type) & ros_message = *(const @(spec.base_type.pkg_name)::@(spec.base_type.type) *)untyped_ros_message;
@[for field in spec.fields]@
// field.name @(field.name)
@ -74,18 +74,21 @@ void convert_ros_message_to_dds__@(spec.base_type.type)(const void * untyped_ros
void publish__@(spec.base_type.type)(DDSDataWriter * topic_writer, const void * ros_message)
{
std::cout << " @(spec.base_type.pkg_name)::type_support::publish__@(spec.base_type.type)()" << std::endl;
//std::cout << " @(spec.base_type.pkg_name)::type_support::publish__@(spec.base_type.type)()" << std::endl;
@(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_ dds_message;
convert_ros_message_to_dds__@(spec.base_type.type)(ros_message, dds_message);
//@(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_ dds_message;
@(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_ * dds_message = @(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_TypeSupport::create_data();
convert_ros_message_to_dds__@(spec.base_type.type)(ros_message, *dds_message);
@(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_DataWriter * data_writer = @(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_DataWriter::narrow(topic_writer);
std::cout << " @(spec.base_type.pkg_name)::type_support::publish__@(spec.base_type.type)() write dds message" << std::endl;
DDS_ReturnCode_t status = data_writer->write(dds_message, DDS_HANDLE_NIL);
//std::cout << " @(spec.base_type.pkg_name)::type_support::publish__@(spec.base_type.type)() write dds message" << std::endl;
DDS_ReturnCode_t status = data_writer->write(*dds_message, DDS_HANDLE_NIL);
if (status != DDS_RETCODE_OK) {
printf("write() failed. Status = %d\n", status);
throw std::runtime_error("write failed");
};
@(spec.base_type.pkg_name)::dds_idl::@(spec.base_type.type)_TypeSupport::delete_data(dds_message);
}

View file

@ -59,6 +59,8 @@ ros_middleware_interface::PublisherHandle create_publisher(const ros_middleware_
throw std::runtime_error("node handle not from this implementation");
}
std::cout << "create_publisher() " << node_handle._implementation_identifier << std::endl;
std::cout << " create_publisher() extract participant from opaque node handle" << std::endl;
DDSDomainParticipant* participant = (DDSDomainParticipant*)node_handle._data;
@ -131,7 +133,7 @@ ros_middleware_interface::PublisherHandle create_publisher(const ros_middleware_
void publish(const ros_middleware_interface::PublisherHandle& publisher_handle, const void * ros_message)
{
std::cout << "publish()" << std::endl;
//std::cout << "publish()" << std::endl;
if (publisher_handle._implementation_identifier != _rti_connext_identifier)
{
@ -140,13 +142,13 @@ void publish(const ros_middleware_interface::PublisherHandle& publisher_handle,
throw std::runtime_error("publisher handle not from this implementation");
}
std::cout << " publish() extract data writer and type code from opaque publisher handle" << std::endl;
//std::cout << " publish() extract data writer and type code from opaque publisher handle" << std::endl;
CustomPublisherInfo * custom_publisher_info = (CustomPublisherInfo*)publisher_handle._data;
DDSDataWriter * topic_writer = custom_publisher_info->topic_writer_;
const ros_dds_connext_static::MessageTypeSupportCallbacks * callbacks = custom_publisher_info->callbacks_;
std::cout << " publish() invoke publish callback" << std::endl;
//std::cout << " publish() invoke publish callback" << std::endl;
callbacks->_publish(topic_writer, ros_message);
}