You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
222 lines
7.5 KiB
222 lines
7.5 KiB
8 years ago
|
@###############################################
|
||
|
@#
|
||
|
@# EmPy template for generating microRTPS_client.cpp file
|
||
|
@#
|
||
|
@###############################################
|
||
|
@# Start of Template
|
||
|
@#
|
||
|
@# Context:
|
||
|
@# - msgs (List) list of all msg files
|
||
|
@# - multi_topics (List) list of all multi-topic names
|
||
|
@###############################################
|
||
|
@{
|
||
|
import genmsg.msgs
|
||
|
import gencpp
|
||
|
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||
|
from px_generate_uorb_topic_files import MsgScope # this is in Tools/
|
||
8 years ago
|
from uorb_rtps_message_ids import * # this is in Tools/
|
||
8 years ago
|
|
||
|
topic_names = [single_spec.short_name for single_spec in spec]
|
||
|
send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND]
|
||
|
recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE]
|
||
|
|
||
|
}@
|
||
|
/****************************************************************************
|
||
|
*
|
||
|
* Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima).
|
||
|
*
|
||
|
* Redistribution and use in source and binary forms, with or without
|
||
|
* modification, are permitted provided that the following conditions are met:
|
||
|
*
|
||
|
* 1. Redistributions of source code must retain the above copyright notice, this
|
||
|
* list of conditions and the following disclaimer.
|
||
|
*
|
||
|
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||
|
* this list of conditions and the following disclaimer in the documentation
|
||
|
* and/or other materials provided with the distribution.
|
||
|
*
|
||
|
* 3. Neither the name of the copyright holder nor the names of its contributors
|
||
|
* may be used to endorse or promote products derived from this software without
|
||
|
* specific prior written permission.
|
||
|
*
|
||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||
|
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||
|
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||
|
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||
|
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||
|
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||
|
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||
|
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||
|
*
|
||
|
****************************************************************************/
|
||
|
|
||
8 years ago
|
#include "microRTPS_transport.h"
|
||
8 years ago
|
#include "microRTPS_client.h"
|
||
8 years ago
|
|
||
|
#include <cinttypes>
|
||
|
#include <cstdio>
|
||
8 years ago
|
#include <ctime>
|
||
|
#include <pthread.h>
|
||
|
|
||
|
#include <microcdr/microCdr.h>
|
||
8 years ago
|
#include <px4_time.h>
|
||
8 years ago
|
#include <uORB/uORB.h>
|
||
|
|
||
|
@[for topic in list(set(topic_names))]@
|
||
|
#include <uORB/topics/@(topic).h>
|
||
7 years ago
|
#include <uORB_microcdr/topics/@(topic).h>
|
||
8 years ago
|
@[end for]@
|
||
|
|
||
|
void* send(void *data);
|
||
|
|
||
|
@[if send_topics]@
|
||
8 years ago
|
void* send(void* /*unused*/)
|
||
8 years ago
|
{
|
||
|
char data_buffer[BUFFER_SIZE] = {};
|
||
|
uint64_t sent = 0, total_sent = 0;
|
||
|
int loop = 0, read = 0;
|
||
|
uint32_t length = 0;
|
||
|
|
||
|
/* subscribe to topics */
|
||
|
int fds[@(len(send_topics))] = {};
|
||
|
|
||
|
// orb_set_interval statblish an update interval period in milliseconds.
|
||
|
@[for idx, topic in enumerate(send_topics)]@
|
||
|
fds[@(idx)] = orb_subscribe(ORB_ID(@(topic)));
|
||
|
orb_set_interval(fds[@(idx)], _options.update_time_ms);
|
||
|
@[end for]@
|
||
|
|
||
|
// microBuffer to serialized using the user defined buffer
|
||
|
struct microBuffer microBufferWriter;
|
||
|
initStaticAlignedBuffer(data_buffer, BUFFER_SIZE, µBufferWriter);
|
||
|
// microCDR structs for managing the microBuffer
|
||
|
struct microCDR microCDRWriter;
|
||
|
initMicroCDR(µCDRWriter, µBufferWriter);
|
||
|
|
||
|
struct timespec begin;
|
||
8 years ago
|
px4_clock_gettime(CLOCK_REALTIME, &begin);
|
||
8 years ago
|
|
||
|
while (!_should_exit_task)
|
||
|
{
|
||
|
bool updated;
|
||
|
@[for idx, topic in enumerate(send_topics)]@
|
||
|
orb_check(fds[@(idx)], &updated);
|
||
|
if (updated)
|
||
|
{
|
||
|
// obtained data for the file descriptor
|
||
8 years ago
|
struct @(topic)_s data;
|
||
8 years ago
|
// copy raw data into local buffer
|
||
8 years ago
|
if (orb_copy(ORB_ID(@(topic)), fds[@(idx)], &data) == 0) {
|
||
|
serialize_@(topic)(&data, data_buffer, &length, µCDRWriter);
|
||
|
if (0 < (read = transport_node->write((char)@(message_id(topic)), data_buffer, length)))
|
||
|
{
|
||
|
total_sent += read;
|
||
|
++sent;
|
||
|
}
|
||
8 years ago
|
}
|
||
|
}
|
||
|
@[end for]@
|
||
|
|
||
|
usleep(_options.sleep_ms*1000);
|
||
|
++loop;
|
||
|
}
|
||
|
|
||
|
struct timespec end;
|
||
8 years ago
|
px4_clock_gettime(CLOCK_REALTIME, &end);
|
||
8 years ago
|
double elapsed_secs = double(end.tv_sec - begin.tv_sec) + double(end.tv_nsec - begin.tv_nsec)/double(1000000000);
|
||
8 years ago
|
printf("\nSENT: %" PRIu64 " messages in %d LOOPS, %" PRIu64 " bytes in %.03f seconds - %.02fKB/s\n",
|
||
8 years ago
|
sent, loop, total_sent, elapsed_secs, (double)total_sent/(1000*elapsed_secs));
|
||
8 years ago
|
|
||
|
return nullptr;
|
||
|
}
|
||
|
|
||
|
static int launch_send_thread(pthread_t &sender_thread)
|
||
|
{
|
||
|
pthread_attr_t sender_thread_attr;
|
||
|
pthread_attr_init(&sender_thread_attr);
|
||
|
pthread_attr_setstacksize(&sender_thread_attr, PX4_STACK_ADJUSTED(4000));
|
||
|
struct sched_param param;
|
||
|
(void)pthread_attr_getschedparam(&sender_thread_attr, ¶m);
|
||
|
param.sched_priority = SCHED_PRIORITY_DEFAULT;
|
||
|
(void)pthread_attr_setschedparam(&sender_thread_attr, ¶m);
|
||
|
pthread_create(&sender_thread, &sender_thread_attr, send, nullptr);
|
||
|
pthread_attr_destroy(&sender_thread_attr);
|
||
|
|
||
|
return 0;
|
||
|
}
|
||
|
@[end if]@
|
||
|
|
||
8 years ago
|
void micrortps_start_topics(struct timespec &begin, int &total_read, uint32_t &received, int &loop)
|
||
8 years ago
|
{
|
||
|
@[if recv_topics]@
|
||
|
|
||
|
char data_buffer[BUFFER_SIZE] = {};
|
||
|
int read = 0;
|
||
8 years ago
|
uint8_t topic_ID = 255;
|
||
8 years ago
|
|
||
|
// Declare received topics
|
||
|
@[for topic in recv_topics]@
|
||
|
struct @(topic)_s @(topic)_data;
|
||
|
orb_advert_t @(topic)_pub = nullptr;
|
||
|
@[end for]@
|
||
|
|
||
|
// microBuffer to deserialized using the user defined buffer
|
||
|
struct microBuffer microBufferReader;
|
||
|
initDeserializedAlignedBuffer(data_buffer, BUFFER_SIZE, µBufferReader);
|
||
|
// microCDR structs for managing the microBuffer
|
||
|
struct microCDR microCDRReader;
|
||
|
initMicroCDR(µCDRReader, µBufferReader);
|
||
|
@[end if]@
|
||
|
|
||
8 years ago
|
px4_clock_gettime(CLOCK_REALTIME, &begin);
|
||
8 years ago
|
_should_exit_task = false;
|
||
|
@[if send_topics]@
|
||
|
|
||
|
// create a thread for sending data to the simulator
|
||
|
pthread_t sender_thread;
|
||
|
launch_send_thread(sender_thread);
|
||
|
@[end if]@
|
||
|
|
||
|
while (!_should_exit_task)
|
||
|
{
|
||
|
@[if recv_topics]@
|
||
|
while (0 < (read = transport_node->read(&topic_ID, data_buffer, BUFFER_SIZE)))
|
||
|
{
|
||
|
total_read += read;
|
||
|
switch (topic_ID)
|
||
|
{
|
||
|
@[for topic in recv_topics]@
|
||
|
case @(message_id(topic)):
|
||
|
{
|
||
|
deserialize_@(topic)(&@(topic)_data, data_buffer, µCDRReader);
|
||
8 years ago
|
if (!@(topic)_pub) {
|
||
8 years ago
|
@(topic)_pub = orb_advertise(ORB_ID(@(topic)), &@(topic)_data);
|
||
8 years ago
|
} else {
|
||
8 years ago
|
orb_publish(ORB_ID(@(topic)), @(topic)_pub, &@(topic)_data);
|
||
8 years ago
|
}
|
||
8 years ago
|
++received;
|
||
|
}
|
||
|
break;
|
||
|
@[end for]@
|
||
|
default:
|
||
|
printf("Unexpected topic ID\n");
|
||
|
break;
|
||
|
}
|
||
|
}
|
||
|
@[end if]@
|
||
|
|
||
|
// loop forever if informed loop number is negative
|
||
8 years ago
|
if (_options.loops >= 0 && loop >= _options.loops) break;
|
||
8 years ago
|
|
||
|
usleep(_options.sleep_ms*1000);
|
||
|
++loop;
|
||
|
}
|
||
|
@[if send_topics]@
|
||
|
_should_exit_task = true;
|
||
8 years ago
|
pthread_join(sender_thread, nullptr);
|
||
8 years ago
|
@[end if]@
|
||
|
}
|