Coder Social home page Coder Social logo

ros2 / ros2_embedded_nuttx Goto Github PK

View Code? Open in Web Editor NEW
72.0 20.0 34.0 80.84 MB

This repository isn't actively being worked on. If you would like to take over maintainership please open a ticket on https://github.com/ros2/ros2

Shell 2.24% Makefile 2.02% C++ 6.22% C 84.44% Python 0.02% Visual Basic 0.01% Perl 0.79% Pascal 0.37% CSS 0.01% PHP 0.01% Assembly 1.47% Bison 0.04% Objective-C 2.31% R 0.06%

ros2_embedded_nuttx's Introduction

ROS 2.0 NuttX prototype

This repository prototypes ROS 2.0 for embedded systems using NuttX, Tinq and the STM32F4 IC.

The prototype has been built in a modular way using the following blocks:

                                        
                              ......    
.....   .....   .....     ............. 
....'  ......  .......    ...       ....
....     ...     ...                 ...
                                    ....
.....  ......   .....             ..... 
.....  ......  .......           .....  
                              ......    
  .                          .....      
.....  ......  ......      ......       
.....  .....'  ......     ..............
.                                      .
                                        

----------------------------------
|           application           |
----------------------------------
|               rcl               |
----------------------------------
|            DDS (Tinq)           |
----------------------------------
|          RTOS (NuttX)           |
__________________________________

|        Hardware (STM32F4)       |
----------------------------------

Milestones

  • Quick overview/understand fo the OMG DDS standart
  • Evaluate different Open Source DDS implementations and select one meant for embedded devices (Tinq selected)
  • Prototype with FreeRTOS (discarded)
  • Prototype with Riot (discarded)
  • Prototype with NuttX (current prototype)
  • Use the network stack to create a simple UDP/IP example over Ethernet
  • NSH (NuttX Shell) infraestructure set up
  • Adjust DDS interfaces to match with NuttX (pseudo-POSIX)
  • DDS compiling and linking on top of NuttX
  • Code small enough to fit in RAM and ROM (refer to this discussion for an approximate size of RAM, current ROM image is about 700 KB)
  • DDS chat application running
  • DDS Debug Shell available
  • Tinq-embedded <-> Tinq Desktop interoperability (DDS embedded - DDS Desktop)
  • DDSIMU demo using ChatMsg type (Tinq Desktop to Tinq Embedded using the same DDS type)
  • Tinq Desktop <-> OpenSplice Desktop interoperability
  • Tinq Embedded <-> OpenSplice Desktop interoperability
  • DDSAccel demo using a ROS Vector3 message
  • ROSIMU demo using a ROS Imu message
  • rcl embedded
  • create ros2_middleware_tinq
  • Hardware frontier

###Hardware ####STM32F4Discovery board Initially we kicked off the prototype with the STM32F4Discovery board together with the STM32F4-BB (this daugher board provides Ethernet). The board is connected to the computer using USB. This connection is used to power up the board, program and debug (through STLINK). PD5, PD6 and GND are used as the serial connection (for development and debugging purposes, NSH, etc). An Ethernet cable is connected from the STM32F4-BB to the working station.

The size of Tinq and NuttX together made us switch into a board with more capacity the STM3240G-eval.

####STM3240G-eval

The STM3240G-eval board includes additional 2 MB SRAM. In order to set it up, connect the USB (flashing purposes, ST-Link), the Ethernet cable, the power connector and finally a 3.3V USB to serial cable:

The TX, RX and GND signals should be connected to CN4 pins 36, 35 and 39 respectively.

To get a serial console type:

 sudo screen /dev/ttyUSB0 115200

(assuming that /dev/ttyUSB0 is the new device that appears when connecting the USB to serial cable)

###Setting it up

####Requirements Install the following requirements:

sudo apt-get install libssl-dev libxml2-dev pkg-config picocom screen libusb-1.0-0-dev gcc-arm-none-eabi
Installing menuconfig
git clone http://ymorin.is-a-geek.org/git/kconfig-frontends
cd kconfig-frontends/
sudo apt-get install autotools-dev autoconf gperf flex bison libncurses5-dev libtool
./bootstrap
./configure
make
sudo make install
sudo /sbin/ldconfig -v
Installing the code
git clone https://github.com/ros2/ros2_embedded_nuttx
cd ros2_embedded_nuttx
rmdir stlink
git clone https://github.com/ros2/stlink
cd stlink
./autogen.sh
./configure
make
cd ..
Installing openocd
cd tools
make openocd
cd ..
Selecting a configuration

For Tinq the one you need to use is:

cd nuttx/tools
./configure.sh stm3240g-eval/dds
cd ..

(alternatively if you work with the STM32F4Discovery board do a ./configure stm32f4discovery/dds )

This configurations selects apps/examples/dds DDS application.

#####Building

cd nuttx/
make 

#####Programming To program the board:

make program

The output should look like:

make program
../tools/openocd/bin/openocd -f board/stm32f4discovery.cfg -c "init" -c "reset halt" -c "flash write_image erase nuttx.bin 0x08000000 bin" -c "verify_image nuttx.bin 0x8000000; reset run; exit"
Open On-Chip Debugger 0.9.0-dev-00112-g1fa24eb (2014-08-19-11:23)
Licensed under GNU GPL v2
For bug reports, read
    http://openocd.sourceforge.net/doc/doxygen/bugs.html
Info : The selected transport took over low-level target control. The results might differ compared to plain JTAG/SWD
adapter speed: 1000 kHz
adapter_nsrst_delay: 100
srst_only separate srst_nogate srst_open_drain connect_deassert_srst
Info : clock speed 1000 kHz
Info : STLINK v2 JTAG v17 API v2 SWIM v0 VID 0x0483 PID 0x3748
Info : using stlink api v2
Info : Target voltage: 3.242300
Info : stm32f4x.cpu: hardware has 6 breakpoints, 4 watchpoints
target state: halted
target halted due to debug-request, current mode: Thread 
xPSR: 0x01000000 pc: 0x080004b0 msp: 0x2000ce18
auto erase enabled
Info : device id = 0x10016413
Info : flash size = 1024kbytes
target state: halted
target halted due to breakpoint, current mode: Thread 
xPSR: 0x61000000 pc: 0x20000042 msp: 0x2000ce18
wrote 655360 bytes from file nuttx.bin in 23.653700s (27.057 KiB/s)
target state: halted
target halted due to breakpoint, current mode: Thread 
xPSR: 0x61000000 pc: 0x2000002e msp: 0x2000ce18
verified 646286 bytes in 5.552209s (113.673 KiB/s)
make: [program] Error 1 (ignored)
Serial console

Using picocom:

picocom /dev/ttyUSB0 -b 115200

Using screen:

screen /dev/ttyUSB0 115200

The advantage of using picocom is that you can scroll while screen does not offer that option by default.

Modifying NuttX

To program the board:

make program

#####Debugging

cd nuttx/
make gdb_server

In another terminal (same directory):

make gdb
Rebasing NuttX

This prototype relies heavily on NuttX. It's recommended to rebase the code frequently with the master branch of NuttX git://git.code.sf.net/p/nuttx/git. The following steps show picture how to do it:

git remote add nuttx git://git.code.sf.net/p/nuttx/git
git fetch nuttx
git checkout master
git rebase nuttx/master
Memory inspection

We can review the memory consumed by the compiled image by:

cd nuttx
source tools/showsize.sh nuttx

Threading

As it's implemented in this prototype, an application has at least 6 threads:

  • dds_thread_core: thread taking care of having a Domain Participant up and handling all the DDS core aspects
  • A thread for each locator (4): This prototype includes a udp pseudo-poll implementation that uses a thread continuosly receiving on each locator (asociated with a file descriptor). The content is stored in a ringbuffer and fetched from the dds_thread_core thread.
  • application threads: each application can launch its own threads using the NuttX primitives. E.g.: ROSIMU demo uses two more threads.

Running in Linux

NuttX includes a simulator that allows to run the applications (with some resctrictions, refer to nuttx/configs/sim/README.txt) directly in Linux. A simple setup can be achieved through:

cd nuttx
make distclean # this is an important step to clean previous builds
cd tools
./configure.sh sim/nsh # make sure you have all the requirements in your Linux machine before compiling (e.g. zlib installed, ...)
cd -
make
./nuttx # you should see the NuttX shell ;)

IGMPv2

NuttX supports only IGMPv2 thereby in order to put force your Linux machine in this mode the following should be done:

sudo bash
echo "2" > /proc/sys/net/ipv4/conf/eth0/force_igmp_version

If you wish to set if to the default value:

sudo bash
echo "0" > /proc/sys/net/ipv4/conf/eth0/force_igmp_version

File structure

tree -L 1
.
├── apps
├── tinq-core
├── misc
├── nuttx
├── NxWidgets
├── rcl
├── README.md
├── ros2_embedded.sublime-project
├── ros2_embedded.sublime-workspace
├── ros2_embedded.tmLanguage
├── stlink
└── tools
  • apps: NuttX applications. The subdirectory examples contains some of the DDS apps.
  • tinq-core: Tinq's DDS implementation hacked to work with NuttX.
  • misc: Variety of things.
  • nuttx: The NuttX RTOS.
  • NxWidgets: a special graphical user interface.
  • rcl: ROS 2 Client Library (Ros Client Library) for embedded.
  • README.md: this file.
  • ros2_embedded.*: Sublime text configuration files.
  • stlink: a modified version of stlink compatible with the implementations.
  • tools: a set of useful tools for development.

DDS Debug Shell

Tinq's DDS implemmentation comes together with a DDS Debug Shell that has proved to be terribly useful to debug problems when working with DDS. The shell can be used prepending !! to any of the available commands:

!!help
Following commands are available:
    ssys                  Display system-specific data.
    stimer                Display the timers.
    sstr                  Display the string cache.
    spool                 Display the pools.
    spoola                Display the pools (extended).
    scx [<cx>]            Display connections.
    scxa [<cx>]           Display connections (extended).
    scxq                  Display queued connections.
    sloc                  Display locators.
    sconfig               Display configuration data.
    sdomain <d> <lf> <rf> Display domain (d) info.
                          <lf> and <rf> are bitmaps for local/remote info.
                          1=Locator, 2=Builtin, 4=Endp, 8=Type, 10=Topic.
    sdisc                 Display discovery info.
    sdisca                Display all discovery info (sdisc + endpoints)
    stype [<name>]        Display Type information.
    sqos                  Display QoS parameters.
    stopic <d> [<name>]   Display Topic information.
    sendpoints            Display the DCPS/RTPS Readers/Writers.
    scache <ep>           Display an RTPS Endpoint Cache.
    sdcache <ep>          Display a DCPS Endpoint Cache.
    qcache <ep> [<query>] Query cache data of the specified endpoint:
                          where: <ep>: endpoint, <query>: SQL Query string.
    sproxy [<ep>]         Display Proxy contexts.
    rproxy [<ep>]         Restart Proxy context.
    seqos <ep>            Display endpoint QoS parameters.
    scrypto <ep>          Display entity crypto parameters.
    sscache               Display security cache.
    rehs                  Request a rehandshake.
    srx                   Display the RTPS Receiver context.
    stx                   Display the RTPS Transmitter context.
    sfd                   Display the status of the file descriptors.
    asp <d>               Assert participant.
    ase <ep>              Assert writer endpoint.
    dtls                  Display DTLS connection related info.
    spdb                  Display the policy database.
    sfwd                  Display the forwarder state.
    ftrace <n>            Start forwarder tracing for <n> events.
    d [<p> [<n>]]         Dump memory.
    da [<p> [<n>]]        Dump memory in ASCII.
    db [<p> [<n>]]        Dump memory in hex bytes.
    ds [<p> [<n>]]        Dump memory in hex 16-bit values.
    dl [<p> [<n>]]        Dump memory in hex 32-bit values.
    dm [<p> [<n>]]        Dump memory in mixed hex/ASCII.
    indent <tab> <n>      Set indent type (if <tab>=1: use TABs).
    taflags <flags>       Set type attribute display flags.
                          <flags>: 1=header, 2=size, 4=elsize, 8=ofs.
    server [<port>]       Start debug server on the given port.
    env                   Display configuration data (=sconf).
    set <var> <value>     Set the configuration variable to given value.
    unset <var>           Unset the configuration variable.
    suspend <value>       Suspend with given mode.
    activate <value>      Activate with given mode.
    help                  Display general help.
    exit                  Close remote connection.

ROS Client Library

The ROS Client Library (rcl) for embedded (implemented under the rcl directory) allows to code ROS applications using the ROS 2 API. Refer to rcl.h for a list of functions.

A simple ROS publisher can be coded with:

#include "rcl.h"

int ros_main(int argc, char *argv[])
{
    /* Init the ROS Client Library */
    rcl_init();
    
    /* Create a ROS node */
    create_node();

    /* Init the dynamic types 
        TODO: abstract this code
    */
    init_types();

    /* Create a publisher
        TODO: specify message types, topics, etc.
    */
    create_publisher();

    int i;
    for (i=0; i<10; i++){
        publish("Hola ROS 2, ¿como estás?");
    }
}

Refer to the rcl/README.md for further instructions on how to use the ROS 2 API to code applications.

Applications

Applications are coded at apps/ros. Refer to apps/ros/publisher for an example.

Communication

Limitations

  • Current example applications (e.g. the ROSIMU demo) publish at about 3 Hz. The reason behind this matter is the 4 threads (one for each locator blocked in a recvfrom call) simulating UDP polling (refer to threading). Without these 4 threads (which are needed for DDS communication), the code has proved to be able to publish at up to 50 Hz. This limitation should be address by implementing real UDP poll() or select() support. Refer to nuttx official repository/TODO, particularly the UDP READ-AHEAD? and NO POLL/SELECT ON UDP SOCKETS tickets.
  • Reception of packages: As mentioned before, this prototype implements UDP poll() using 4 threads (one for each locator) blocked "reading" all the time. If a package arrives and there's nobody reading (the corresponding thread should be scheduled at that time) then the kernel dumps the package. This causes that only "some packages" coming from the publising side will be received and processed properly. This log presents the rosimu_subscriber application running in the embedded board and receiving packages from the Desktop (running OpenSplice). The header.seq should increment by one every time however we are getting 4, 11, 19, 28, ...
  • Tinq QoS parameters hasn't been tested. There's no guarantee that it'll work.
  • In NuttX we can't simultaneously read and write from a socket (refer to brunodebus/tinq-core#7 (comment)). Tinq has been implemented with this assumption in mind thereby a set of fixes were applied to make it work.
  • The implementation does not support different message types with the same topic name (issue). Refer to the discussion.
  • Tinq implementation does not interoperate with RTI's Connext. Refer to the issue.

ros2_embedded_nuttx's People

Contributors

esteve avatar gregory-nutt avatar vmayoral avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

ros2_embedded_nuttx's Issues

mbtowc implementation

A quick fix has been applied (refer to commit 580a659). Ideally it should be implemented. Refer to the commit message for details on how to proceed.

STM3240G-EVAL 16 Mbit memory

The new board should include 2MB of additional SRAM but it's not present in NuttX nor seems to allow to run the applications.

No dynamical allocations

Given the issues obtained with dynamical memory a new branch could be created to work on a version that does not use dynamical allocations.

serial console with picocom

Floats or doubles are not print appropriately:

Imu ROS message received:
    header.seq=13979
    header.stamp.sec=0
    header.stamp.nanosec=0
    header.frame_id=1677744932
    orientation.x=
    orientation.y=
    orientation.z=0
    orientation.w=
    orientation_covariance=        
    angular_velocity_x=
    angular_velocity_y=
    angular_velocity_z=
    angular_velocity_covariance=        
    linear_acceleration_x=0
    linear_acceleration_y=0
    linear_acceleration_z=0
    linear_acceleration_covariance=        
**************************************
Imu ROS message received:
    header.seq=13986
    header.stamp.sec=0
    header.stamp.nanosec=0
    header.frame_id=1677744932
    orientation.x=
    orientation.y=
    orientation.z=0
    orientation.w=
    orientation_covariance=        
    angular_velocity_x=
    angular_velocity_y=
    angular_velocity_z=
    angular_velocity_covariance=        
    linear_acceleration_x=0
    linear_acceleration_y=0
    linear_acceleration_z=0
    linear_acceleration_covariance=        

....

UDP polling

Need to address 408d1da. The current solution just allows to continue with the prototype but this matter should be properly addressed.

Tinq Desktop <-> RTI Connext interoperability

When tested with RTI Connext it seems that discovery is not finishing properly (using the Desktop impl):

!!sdisca
Domain 0 (pid=174): {1}
    GUID prefix: 8f937eb8:00ae729f:03e90000
    RTPS Protocol version: v2.1
    Vendor Id: 1.14 - Technicolor, Inc. - Qeo
    Technicolor DDS version: 4.0-0, Forward: 0
    SecureTransport: none
    Authorisation: Authenticated
    Entity name: Technicolor Chatroom
    Flags: Enabled
    Meta Unicast: 
        UDP:172.23.1.215:7758(3) {MD,UC} H:3
    Meta Multicast: 
        UDP:239.255.0.1:7400(4) {MD,MC} H:4
    Default Unicast: 
        UDP:172.23.1.215:7759(1) {UD,UC} H:1
    Default Multicast: 
        UDP:239.255.0.1:7401(2) {UD,MC} H:2
    Manual Liveliness: 0
    Lease duration: 50.000000000s
    Endpoints: 10 entries (5 readers, 5 writers).
        000001-3, {22}, InlineQoS: No, Writer, imu/simple_msgs::dds_::Vector3_
        000002-4, {24}, InlineQoS: No, Reader, imu/simple_msgs::dds_::Vector3_
    Topics: 
        BuiltinParticipantMessageReader/ParticipantMessageData 
        BuiltinParticipantMessageWriter/ParticipantMessageData 
        SEDPbuiltinPublicationsReader/PublicationBuiltinTopicData 
        SEDPbuiltinPublicationsWriter/PublicationBuiltinTopicData 
        SEDPbuiltinSubscriptionsReader/SubscriptionBuiltinTopicData 
        SEDPbuiltinSubscriptionsWriter/SubscriptionBuiltinTopicData 
        SPDPbuiltinParticipantReader/ParticipantBuiltinTopicData 
        SPDPbuiltinParticipantWriter/ParticipantBuiltinTopicData 
        imu/simple_msgs::dds_::Vector3_ 
    Security: level=Unclassified, access=any, RTPS=clear
    Resend period: 10.000000000s
    Destination Locators: 
        UDP:239.255.0.1:7400(4) {MD,MC} H:4
        TCP:239.255.0.1:7400 {MD,MC}
    Discovered participants:
        Peer #0: {25} - Local activity: 9.07s
        GUID prefix: ac1701d7:00007297:00000001
        RTPS Protocol version: v2.1
        Vendor Id: 1.1 - Real-Time Innovations, Inc. - Connext DDS
        Meta Unicast: 
            UDPv6:2:7:207:::7410 {MD,UC}
            UDP:172.23.1.215:7410 {MD,UC}
        Meta Multicast: 
            UDP:239.255.0.1:7400(4) {MD,MC} H:4
        Default Unicast: 
            UDPv6:2:7:207:::7411 {UD,UC}
            UDP:172.23.1.215:7411 {UD,UC}
        Manual Liveliness: 0
        Lease duration: 100.000000000s
        Endpoints: 4 entries (2 readers, 2 writers).
        Topics:  <none>
        Source: 
            UDP:172.23.1.215:35149 {MD,UC}
        Timer = 90.30s

Seems like SPDP does its job but not SEDP.

Tinq Desktop <-> OpenSplice interoperability

It doesn't seem straightforward to interoperate between the different DDS implementations.

The types in OpenSplice are of the kind:
simple_msgs::dds_::Vector3_

When trying to set up this type in Tinq i get a segmentation fault:

!!sdisca
...
            UDP:239.255.0.1:7400(4) {MD,MC} H:4
        Default Unicast: 
            UDP:172.23.1.215:7701 {UD,UC}
        Default Multicast: 
            UDP:239.255.0.1:7401(2) {UD,MC} H:2
        Manual Liveliness: 0
        Lease duration: 50.000000000s
        Endpoints: 8 entries (4 readers, 4 writers).
Segmentation fault (core dumped)

There's a null pointer somewhere an an issue with these kind of type name.

IGMP calls in NuttX

Tinq DDS is implementing IGMP calls in the following manner:

@vmayoral We use setsockopt IP_ADD_MEMBERSHIP to control multicast group membership (see dds/src/trans/ip/ri_udp.c around line 835) . This triggers the Linux network stack to send out the initial IGMP message (and to reply to membership queries) . Looks like NuttX does not support this (see nuttx/TODO around line 866).. they talk about ioctl(SIOCSIPMSFILTER) and that indeed seems to force the initial send.

Review whether NuttX supports this API and if not make it match with the one used in the apps/examples/igmp.

Mutex not returning

There's some issue in the code in this line https://github.com/vmayoral/ros2_embedded_nuttx/blob/master/nuttx/sched/pthread/pthread_mutexlock.c#L166.

#0  pthread_mutex_lock (mutex=0x200071e4) at pthread/pthread_mutexlock.c:121
#1  0x080651a0 in rcl_access (p=0x20000340 <dt_byte>) at ../../../dds/src/co/thread.c:444
#2  0x08023b50 in xt_type_delete (tp=0x20000340 <dt_byte>) at ../../../dds/src/xtypes/xtypes.c:2711
#3  0x08038338 in tsm_create_array (lp=0x100047b8, tsm=0x1000327c, iflags=0x10003288) at ../../../dds/src/xtypes/tsm.c:343
#4  0x0803854a in tsm_create_type (lp=0x100047b8, tsm=0x1000327c, iflags=0x10003288) at ../../../dds/src/xtypes/tsm.c:452
#5  0x08037e6c in tsm_create_struct_union (lp=0x100047b8, tsm=0x1000327c, iflags=0x10003288) at ../../../dds/src/xtypes/tsm.c:142
#6  0x0801e316 in DDS_DynamicType_register (tc=0x809f804 <dds_participant_msg_tsm+56>) at ../../../dds/src/xtypes/xtypecode.c:208
#7  0x0807f030 in msg_init () at ../../../dds/src/disc/disc_msg.c:193
#8  0x08081eb2 in spdp_init () at ../../../dds/src/disc/disc_spdp.c:91
#9  0x08053f02 in disc_init () at ../../../dds/src/disc/disc_main.c:992
#10 0x08015c56 in dds_init () at ../../../dds/src/dds/dds.c:1420
#11 0x08044024 in DDS_DomainParticipantFactory_create_participant (domain=0, qos=0x0, listener=0x0, mask=(unknown: 0))
    at ../../../dds/src/dcps/dcps_dpfact.c:76
#12 0x08011064 in dds_chat_main (argc=1, argv=0x10003754) at main.c:532
#13 0x0800348e in task_start () at task/task_start.c:139
#14 0x00000000 in ?? ()

NuttX network configuration

In NuttX, the result of executing !!sdisc:

Domain 0 (pid=95): {1}
        GUID prefix: 6002b4df:005f0004:00060000
        RTPS Protocol version: v2.1
        Vendor Id: 1.14 - Technicolor, Inc. - Qeo
        Technicolor DDS version: 4.0-0
        Entity name: ROS 2.0 embedded
        Flags: Enabled
        Meta Multicast: 
                UDP:239.255.0.1:7400(2) {MD,MC} H:2
        Default Multicast: 
                UDP:239.255.0.1:7401(1) {UD,MC} H:1
        Manual Liveliness: 0
        Lease duration: 50.000000000s
        Endpoints: 10 entries (5 readers, 5 writers).
        Resend period: 10.000000000s
        Destination Locators: 
                UDP:239.255.0.1:7400(2) {MD,MC} H:2
        Discovered participants: <none>

while in Ubuntu:

Domain 0 (pid=4): {1}
    GUID prefix: 52b5027c:00040952:03e90000
    RTPS Protocol version: v2.1
    Vendor Id: 1.14 - Technicolor, Inc. - Qeo
    Technicolor DDS version: 4.0-0, Forward: 0
    SecureTransport: none
    Authorisation: Authenticated
    Entity name: Technicolor Chatroom
    Flags: Enabled
    Meta Unicast: 
        UDP:192.168.0.2:7418(4) {MD,UC} H:4
        UDP:192.168.1.185:7418(5) {MD,UC} H:5
    Meta Multicast: 
        UDP:239.255.0.1:7400(6) {MD,MC} H:6
    Default Unicast: 
        UDP:192.168.0.2:7419(1) {UD,UC} H:1
        UDP:192.168.1.185:7419(2) {UD,UC} H:2
    Default Multicast: 
        UDP:239.255.0.1:7401(3) {UD,MC} H:3
    Manual Liveliness: 0
    Lease duration: 50.000000000s
    Endpoints: 10 entries (5 readers, 5 writers).
    Security: level=Unclassified, access=any, RTPS=clear
    Resend period: 10.000000000s
    Destination Locators: 
        UDP:239.255.0.1:7400(6) {MD,MC} H:6
        TCP:239.255.0.1:7400 {MD,MC}
    Discovered participants: <none>

Networking setup needs to be inspected in NuttX.

Tinq nested types support over the wire

@jvoe I'm trying to set up an Imu32 (using 32-bit types) between Desktop and Embedded. I did several prototypes with non nested types. E.g: vector_float32_publisher:

typedef struct _Vector3__st
{
    float x_;
    float y_;
    float z_;
} Vector3_t;

defines the type support here like this:

                ...
        tb = DDS_DynamicTypeBuilderFactory_create_type (desc);
        if (!tb)
            break;

        md = DDS_MemberDescriptor__alloc ();
        if (!md)
            break;

        /* Add structure members: */
        md->name = M_0;
        md->id = 0;
        md->type = DDS_DynamicTypeBuilderFactory_get_primitive_type (DDS_FLOAT_32_TYPE);
        md->index = 0;
        rc = DDS_DynamicTypeBuilder_add_member (tb, md);
        if (rc)
            break;

        md->name = M_1;
        md->id = 1;
        md->type = DDS_DynamicTypeBuilderFactory_get_primitive_type (DDS_FLOAT_32_TYPE);
        md->index = 1;
        rc = DDS_DynamicTypeBuilder_add_member (tb, md);
        if (rc)
            break;

        md->name = M_2;
        md->id = 2;
        md->type = DDS_DynamicTypeBuilderFactory_get_primitive_type (DDS_FLOAT_32_TYPE);
        md->index = 2;
        rc = DDS_DynamicTypeBuilder_add_member (tb, md);
        if (rc)
            break;

        /* Finally create the Dynamic Type t. */
        Vector3_type = DDS_DynamicTypeBuilder_build (tb);
        if (!Vector3_type)
            break;
                ...

This kind of construction works great for non-nested types however for nested types, what primitives should i use to construct support for the type?. To put in in context, i'm trying to provide support for this type:

typedef struct Time_
{

  typedef int32_t _sec_type;
  _sec_type sec;

  typedef uint32_t _nanosec_type;
  _nanosec_type nanosec;

} Time_t; // struct Time_


typedef struct Header_
{
  typedef uint32_t _seq_type;
  _seq_type seq;

  Time_t stamp;

  typedef char* _frame_id_type;
  _frame_id_type frame_id;

} Header_t;

typedef struct Quaternion32_
{
  typedef float _x_type;
  _x_type x;

  typedef float _y_type;
  _y_type y;

  typedef float _z_type;
  _z_type z;

  typedef float _w_type;
  _w_type w;

} Quaternion32_t ;

typedef struct _Vector3__st
{
    float x_;
    float y_;
    float z_;
} Vector3_t;

typedef struct Imu32_
{

  Header_t header;

  Quaternion32_t orientation;
  float orientation_covariance[9];

  Vector3_t angular_velocity;
  float angular_velocity_covariance[9];

  Vector3_t linear_acceleration;
  float linear_acceleration_covariance[9];

} Imu32_t; // struct Imu32_

Use CCM memory

Branch https://github.com/ros2/ros2_embedded_nuttx/tree/ccm pretends to use CCM memory following http://www.nuttx.org/doku.php?id=wiki:howtos:stm32-ccm-alloc however when reseting the board:

AB�DF
up_assert: Assertion failed at file:mm_heap/mm_initialize.c line: 100
up_dumpstate: sp:         2000ced4
up_dumpstate: stack base: 2000cf94
up_dumpstate: stack size: 00001000
up_stackdump: 2000cec0: 2000ced4 2000cec0 2000cec0 2000ced4 00000000 00000000 00000000 2000cee4
up_stackdump: 2000cee0: 08001ce3 2000ced4 20002480 00001000 2000cf94 2000cf04 08001d6d 00000064
up_stackdump: 2000cf00: 68686868 00000064 080a6d3c 2000cf14 08006c8d 0000000d 00013068 2000cf98
up_stackdump: 2000cf20: 2000b050 2000cf2c 08006e01 10020000 00000000 2000cf3c 08006de5 00000000
up_stackdump: 2000cf40: 00013068 2000cf98 2000b050 00013068 0000000c 2000cf5c 08007027 00013068
up_stackdump: 2000cf60: 2000cf98 2000cf6c 08002c11 2000cf74 00013068 2000cf98 00000010 2000cf84
up_stackdump: 2000cf80: 08000565 2000227c 080b6ea8 00000000 ffffffff 68686868 68686868 68686868

NuttX Linux simulation (previous "using Qemu for simulation")

@CodeBot9000 in order to allow others to use our current implementation we are trying to make it work in Qemu. While using this configuration i get the following error:

 make
make[1]: Entering directory `/home/victor/Dropbox/OSRF/ros2_embedded_nuttx/nuttx/tools'
mkconfig.c:1:0: error: CPU you selected does not support x86-64 instruction set
 /****************************************************************************
 ^
mkconfig.c:1:0: error: CPU you selected does not support x86-64 instruction set
cfgdefine.c:1:0: error: CPU you selected does not support x86-64 instruction set
 /****************************************************************************
 ^
cfgdefine.c:1:0: error: CPU you selected does not support x86-64 instruction set
make[1]: *** [mkconfig] Error 1
make[1]: Leaving directory `/home/victor/Dropbox/OSRF/ros2_embedded_nuttx/nuttx/tools'
make: *** [tools/mkconfig] Error 2

@NuttX i tried activating several x86-64 options through menuconfig but it didn't help. Do you know if there's a way to build NuttX for Qemu on 64 bit machines?.

Tinq same topic, different message

Tinq has issues dealing with messages coming from the same topic but with different msg types. For now it seems that only one type per topic should be used.

Packages sent by the embedded board corrupted

It seems like the embedded boards sends bad locator information. Particularly:

PID_DEFAULT_LOCATOR_UNICAST
|_ Locator
              |_ kind

We expect 0x0...01 but get we 0x2000e201. The IP addresses of the locator also seem to have :: as a prefix which shouldn't happen.

Parameters configured from static variables forced to 1

Parameters are set to be invalid. Why does this happen. If this line is removed or the code forces parameters to have valid values (e.g. here) the code crashes at locator_pool_init.

Because !locrefs->reserved and !locators->reserved are 1:

nsh> dds_chat
Network configured, starting DDS chat:
List pools created.
String pool initialized.
Typecode pools created.
Typesupport inAssertion failed at file:mm_free.c line: 137
sp:         10003090
stack base: 10003750
stack size: 000007e4
10003080: 10003080 10003080 100030a0 00000000 00000000 00000000 100030a0 08001c5b
100030a0: 10003090 10002b00 000007e4 10003750 100030b8 08001cd9 00000089 080a3a50
100030c0: 100030c8 08006f37 10003780 2000e068 10002f68 1000fff8 1000fff8 10003778
100030e0: 100030e8 08006ac3 00000004 10003780 100030f8 08067537 00000000 10003788
10003100: 200003dc 10003780 10003110 08022cc7 00000002 100037a8 2000044c 00000008
10003120: 00000000 0000000d 10003130 080233e9 10003138 08020f75 10003140 08013935
10003140: 10003148 08004303 080ac678 10002b00 0809f3e9 10002bd0 10003160 080043c9
10003160: 10002cac 00000012 00000001 10002b00 10003178 080034ed 10003190 00000001
10003180: 080ac678 10002b00 10003190 08068a2b 100031fc 080ac6e0 00000082 04040000
100031a0: 100031a8 0009f37d 00000000 00000100 100031fc 00000000 100031c0 0809e3cd
100031c0: 1000330c 080a5fd8 00000100 100031fc 0809e3d9 08006255 00000025 100031fc
100031e0: 000000ff 00000000 100031f8 0806922d 00000001 10003204 00000000 61636f6c
10003200: 5f726f74 6c6f6f70 696e695f 20292874 6c696166 203a6465 6f727265 203d2072
10003220: 00000034 10003228 00000061 20000000 2000e068 20000000 10003240 08002741
10003240: 00000a00 20000000 00000000 0004083c 0000000c 40020c00 00000003 10000000
10003260: 00003268 10003268 10003270 00000000 100032b0 3b9aca00 00000000 0ee6b280
10003280: 00000000 0ee6b280 00000000 100032b0 00000000 0ee6b280 00000008 0000203a
100032a0: 00000000 100032a8 100032d0 00000000 0674c008 0ee6b280 00000000 00000000
100032c0: 100032c8 0806831d b98eb46d 10002b00 0674c008 100032d8 100032e0 600434df
100032e0: 0674c008 100032e8 100032f8 600434df 100032f8 0801ca17 10003538 1000330c
10003300: 10003320 08014765 080a5fd8 00000004 1000336c 00000004 00000000 00000000
10003320: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003340: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003360: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003380: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000065
100033a0: 00000000 20000000 00000000 100033b0 00000065 20000000 00000000 20000000
100033c0: 100033c8 08002741 00000000 20000000 00000000 0004083c 0000000c 40020c00
100033e0: 00000003 10000000 0000ddd8 100033f0 100033f8 00000000 10003400 0800291b
10003400: 10003408 00000010 10003410 0800299f 10003418 00000004 10003420 080015a1
10003420: 10003438 00000036 10003430 00000000 10003498 0800047f 10003480 00000000
10003440: 00000000 00000000 00000000 10003498 00000000 00000000 00000000 00000000
10003460: 20000000 00000000 000000a2 00000000 00000000 08002741 08001356 01000000
10003480: 0100000a 2000000c 00003490 00000000 00000000 00000000 100034a0 0800217b
100034a0: 100034f0 00000000 10002ef7 10002c14 00000000 010a0000 20000000 10000070
100034c0: 00000000 00000027 100034d0 080983ef 00000000 00000027 10002ed0 00000001
100034e0: 00000000 00000027 10000070 10002c14 10002c00 10002b00 10003500 10003500
10003500: 10003508 10002cac 10002ed0 10002b00 10003518 10003518 00000034 10003564
10003520: 10003528 080052f5 00000004 10003564 00000034 100035e8 00000001 00000000
10003540: 00000000 00002000 00000001 00000000 00000000 00001000 00000001 00000000
10003560: 00000000 00000800 00000001 00000000 00000000 00000400 00000001 00000000
10003580: 00000000 00000200 00000001 00000000 00000000 00000100 00000001 00000000
100035a0: 00000000 00000080 00000001 00000000 00000000 00000040 00000000 00000000
100035c0: 20005164 00000004 20004934 00004000 0000000c 10003528 100035e0 08048045
100035e0: 0000f3e9 00000000 00000000 00000000 10003754 00000001 7ffffffe 00000006
10003600: 10003620 00000001 00000000 00000000 10003620 08011039 00000000 00000000
10003620: 10003754 00000001 00ffffff 00000000 00000000 00000000 00000000 00000000
10003640: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003660: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003680: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
100036a0: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
100036c0: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
100036e0: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003700: 00000000 00000000 00000000 00000000 00000000 00000000 00000000 00000000
10003720: 00000000 00000000 00000000 00000000 10003738 0800348f 00000000 00000000
10003740: 10002b00 00000001 00000000 00000000 00000000 1000375c 00000000 6e6f6e3c
up_hardfault: PANIC!!! Hard fault: 40000000
Assertion failed at file:armv7-m/up_hardfault.c line: 183
sp:         10002f48
stack base: 10003750
stack size: 000007e4
ERROR: Stack pointer is not within the allocated stack
R0: 00000004 10009b90 10009b88 0fffb6c8 00000000 00000000 00000000 10003018
R8: 00000000 00000000 00000000 00000000 000007ff 10003018 08006ce9 08006f1a
xPSR: 81000000 PRIMASK: 00000000 CONTROL: 00000000

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.