VRBRAIN / mk: updated all makefiles and ROMFS for all VirtualRobotix boards

This commit is contained in:
LukeMike 2016-07-05 17:58:28 +02:00 committed by Andrew Tridgell
parent cab1acee46
commit bda59b890d
230 changed files with 7127 additions and 4891 deletions

View File

@ -0,0 +1,320 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# To disable APM startup add a /fs/microsd/APM/nostart file
# check for an old file called APM, caused by
# a bug in an earlier firmware release
if [ -f /fs/microsd/APM ]
then
echo "APM file found - renaming"
mv /fs/microsd/APM /fs/microsd/APM.old
fi
if [ -f /fs/microsd/APM/nostart ]
then
echo "APM/nostart found - skipping APM startup"
sh /etc/init.d/rc.error
fi
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "binfs already mounted"
else
echo "Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
set sketch NONE
if rm /fs/microsd/APM/boot.log
then
echo "removed old boot.log"
fi
set logfile /fs/microsd/APM/BOOT.LOG
if [ ! -f /bin/ArduPilot ]
then
echo "/bin/ardupilot not found"
sh /etc/init.d/rc.error
fi
if mkdir /fs/microsd/APM > /dev/null
then
echo "Created APM directory"
fi
echo "Starting uORB"
if uorb start
then
echo "uorb started OK"
else
sh /etc/init.d/rc.error
fi
echo "Starting ADC"
if adc start
then
echo "ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "Starting APM sensors"
set INTERNAL_MS5611 false
set INTERNAL_MPU6000 false
set INTERNAL_MPU9250 false
set INTERNAL_HMC5883 false
set EXTERNAL_EXP_MS5611 false
set EXTERNAL_EXP_MPU6000 false
set EXTERNAL_EXP_HMC5983 false
set EXTERNAL_IMU_MS5611 false
set EXTERNAL_IMU_MPU6000 false
set EXTERNAL_IMU_HMC5983 false
set EXTERNAL_GPS_HMC5883 false
if ver hwcmp VRBRAIN_V51
then
echo "Detected VRBRAINv51 board"
set INTERNAL_MS5611 true
set INTERNAL_MPU6000 true
set INTERNAL_HMC5883 true
set EXTERNAL_GPS_HMC5883 true
fi
if ver hwcmp VRBRAIN_V52
then
echo "Detected VRBRAINv52 board"
set INTERNAL_MS5611 true
set INTERNAL_MPU6000 true
set INTERNAL_HMC5883 true
set EXTERNAL_GPS_HMC5883 true
fi
if ver hwcmp VRBRAIN_V54
then
echo "Detected VRBRAINv54 board"
set INTERNAL_MS5611 true
set INTERNAL_MPU6000 true
set INTERNAL_HMC5883 true
set EXTERNAL_GPS_HMC5883 true
fi
if ver hwcmp VRCORE_V10
then
echo "Detected VRCOREv10 board"
set INTERNAL_MS5611 true
set INTERNAL_MPU6000 true
set EXTERNAL_GPS_HMC5883 true
fi
if ver hwcmp VRUBRAIN_V51
then
echo "Detected VRUBRAINv51 board"
set INTERNAL_MS5611 true
set INTERNAL_MPU6000 true
set EXTERNAL_GPS_HMC5883 true
fi
if ver hwcmp VRUBRAIN_V52
then
echo "Detected VRUBRAINv52 board"
set INTERNAL_MS5611 true
set INTERNAL_MPU6000 true
set EXTERNAL_GPS_HMC5883 true
fi
if [ $INTERNAL_MS5611 == true ]
then
echo "Starting MS5611 Internal"
if ms5611 -s start
then
echo "MS5611 Internal started OK"
else
echo "MS5611 Internal start failed"
sh /etc/init.d/rc.error
fi
fi
if [ $EXTERNAL_GPS_HMC5883 == true ]
then
echo "Starting HMC5883 External GPS"
if hmc5883 -C -X start
then
echo "HMC5883 External GPS started OK"
else
echo "HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
fi
if [ $INTERNAL_HMC5883 == true ]
then
echo "Starting HMC5883 Internal"
if hmc5883 -C -R 12 -I start
then
echo "HMC5883 Internal started OK"
else
echo "HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
fi
if [ $INTERNAL_MPU6000 == true ]
then
echo "Starting MPU6000 Internal"
if mpu6000 -R 12 start
then
echo "MPU6000 Internal started OK"
else
echo "[APM] MPU6000 Internal start failed"
sh /etc/init.d/rc.error
fi
fi
if [ $INTERNAL_MPU9250 == true ]
then
echo "Starting MPU9250 Internal"
if mpu9250 -R 4 start
then
echo "MPU9250 Internal started OK"
else
echo "[APM] MPU9250 Internal start failed"
sh /etc/init.d/rc.error
fi
fi
# optional ETS airspeed sensor
if ets_airspeed start
then
echo "Found ETS airspeed sensor"
else
if ets_airspeed start -b 2
then
echo "Found ETS airspeed sensor"
else
echo "ETS airspeed sensor start failed"
fi
fi
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
else
if meas_airspeed start -b 2
then
echo "Found MEAS airspeed sensor"
else
echo "MEAS airspeed sensor start failed"
fi
fi
# optional Range Finder sensor
if ll40ls -X start
then
echo "Found external ll40ls sensor"
fi
if [ $LL_I2C_AUX == true ]
then
if ll40ls -I start
then
echo "Found internal ll40ls sensor"
fi
fi
if [ $LL_PWM_INPUT == true ]
then
# optional PWM input driver
if pwm_input start
then
echo "started pwm_input driver"
if ll40ls start pwm
then
echo "Found ll40ls sensor PWM"
fi
fi
fi
if trone start
then
echo "Found trone sensor"
fi
if mb12xx start
then
echo "Found mb12xx sensor"
fi
# Starting Optional PX4Flow sensor
if px4flow start
then
echo "Found PX4Flow sensor"
fi
if irlock start
then
echo "Found IR-Lock and Pixy vision sensor"
else
if irlock start -b 2
then
echo "Found IR-Lock and Pixy vision sensor"
else
echo "IR-Lock and Pixy vision sensor start failed"
fi
fi
echo "Starting MTD driver"
if mtd start /fs/mtd
then
echo "MTD driver started OK"
else
echo "MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "MTD driver read test"
if mtd readtest /fs/mtd
then
echo "MTD driver readtest OK"
else
echo "MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "FMU mode PWM"
if fmu mode_pwm
then
echo "Set FMU mode_pwm"
fi
# optional PWM input driver
if pwm_input start
then
echo "started pwm_input driver"
fi
echo "Starting ArduPilot"
if ArduPilot start
then
echo "ArduPilot started OK"
else
echo "ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "Exiting from nsh shell"
exit
echo "rc.APM finished"

View File

@ -0,0 +1,14 @@
echo "Error in startup"
tone_alarm MNCC
if [ $HAVE_RGBLED == 1 ]
then
rgbled rgb 16 0 0
fi
nshterm /dev/ttyACM0 &
sleep 1
nshterm /dev/ttyS0 &
sleep 1
exit

140
mk/VRBRAIN/ROMFS/init.d/rcS Normal file
View File

@ -0,0 +1,140 @@
#!nsh
#
# VRBRAIN startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
#
if rgbled start
then
set HAVE_RGBLED 1
# show startup white
rgbled rgb 16 16 16
else
set HAVE_RGBLED 0
fi
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
set HAVE_MICROSD 1
# Start playing the startup tune
if [ -f /etc/tones/startup ]
then
tone_alarm /etc/tones/startup
else
tone_alarm 1
fi
else
set HAVE_MICROSD 0
echo "Trying format of microSD"
tone_alarm MBAGP
if mkfatfs /dev/mmcsd0
then
echo "microSD card formatted"
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "format succeeded"
set HAVE_MICROSD 1
if [ -f /etc/tones/startup ]
then
tone_alarm /etc/tones/startup
else
tone_alarm 1
fi
else
echo "mount failed"
tone_alarm MNBG
if [ $HAVE_RGBLED == 1 ]
then
rgbled rgb 16 0 0
fi
fi
else
echo "format failed"
tone_alarm MNBGG
if [ $HAVE_RGBLED == 1 ]
then
rgbled rgb 16 0 0
fi
fi
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
if [ $HAVE_MICROSD == 0 ]
then
if usb_connected
then
echo "Opening USB nsh"
else
echo "booting with no microSD"
set HAVE_MICROSD 1
fi
fi
# if this is an APM build then there will be a rc.APM script
# from an EXTERNAL_SCRIPTS build option
if [ -f /etc/init.d/rc.APM -a $HAVE_MICROSD == 1 -a ! -f /fs/microsd/APM/nostart ]
then
echo Running rc.APM
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
else
nshterm /dev/ttyACM0 &
fi

View File

@ -1,196 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# To disable APM startup add a /fs/microsd/APM/nostart file
# check for an old file called APM, caused by
# a bug in an earlier firmware release
if [ -f /fs/microsd/APM ]
then
echo "[APM] APM file found - renaming"
mv /fs/microsd/APM /fs/microsd/APM.old
fi
if [ -f /fs/microsd/APM/nostart ]
then
echo "[APM] APM/nostart found - skipping APM startup"
sh /etc/init.d/rc.error
fi
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APM] binfs already mounted"
else
echo "[APM] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APM] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if rm /fs/microsd/APM/boot.log
then
echo "[APM] Removed old boot.log"
fi
set logfile /fs/microsd/APM/BOOT.LOG
if [ ! -f /bin/ArduPilot ]
then
echo "[APM] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
if mkdir /fs/microsd/APM > /dev/null
then
echo "[APM] Created APM directory"
fi
echo "[APM] Starting UORB"
if uorb start
then
echo "[APM] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting ADC"
if adc start
then
echo "[APM] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting APM sensors"
echo "[APM] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APM] MS5611 onboard started OK"
else
echo "[APM] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APM] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APM] HMC5883 External GPS calibrate OK"
else
echo "[APM] HMC5883 External GPS calibrate failed"
fi
else
echo "[APM] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 Internal"
if hmc5883 -I start
then
echo "[APM] HMC5883 Internal started OK"
if hmc5883 -I calibrate
then
echo "[APM] HMC5883 Internal calibrate OK"
else
echo "[APM] HMC5883 Internal calibrate failed"
fi
else
echo "[APM] HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APM] MPU6000 onboard started OK"
else
echo "[APM] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 External"
if mpu6000 -X start
then
echo "[APM] MPU6000 external started OK"
else
echo "[APM] MPU6000 external start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APM] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APM] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APM] MTD driver started OK"
else
echo "[APM] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APM] MTD driver readtest OK"
else
echo "[APM] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APM] VROUTPUT driver started OK"
#else
# echo "[APM] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APM] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APM] VRINPUT driver started OK"
#else
# echo "[APM] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APM] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APM] ArduPilot started OK"
else
echo "[APM] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Exiting from nsh shell"
exit
echo "[APM] Script finished"

View File

@ -1,168 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APMNS] binfs already mounted"
else
echo "[APMNS] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APMNS] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if [ ! -f /bin/ArduPilot ]
then
echo "[APMNS] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting UORB"
if uorb start
then
echo "[APMNS] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting ADC"
if adc start
then
echo "[APMNS] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting APM sensors"
echo "[APMNS] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APMNS] MS5611 onboard started OK"
else
echo "[APMNS] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APMNS] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APMNS] HMC5883 External GPS calibrate OK"
else
echo "[APMNS] HMC5883 External GPS calibrate failed"
fi
else
echo "[APMNS] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 Internal"
if hmc5883 -I start
then
echo "[APMNS] HMC5883 Internal started OK"
if hmc5883 -I calibrate
then
echo "[APMNS] HMC5883 Internal calibrate OK"
else
echo "[APMNS] HMC5883 Internal calibrate failed"
fi
else
echo "[APMNS] HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APMNS] MPU6000 onboard started OK"
else
echo "[APMNS] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 External"
if mpu6000 -X start
then
echo "[APMNS] MPU6000 external started OK"
else
echo "[APMNS] MPU6000 external start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APMNS] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APMNS] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APMNS] MTD driver started OK"
else
echo "[APMNS] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APMNS] MTD driver readtest OK"
else
echo "[APMNS] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APMNS] VROUTPUT driver started OK"
#else
# echo "[APMNS] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APMNS] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APMNS] VRINPUT driver started OK"
#else
# echo "[APMNS] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APMNS] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APMNS] ArduPilot started OK"
else
echo "[APMNS] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Exiting from nsh shell"
exit
echo "[APMNS] Script finished"

View File

@ -1,7 +0,0 @@
echo "Error in startup"
nshterm /dev/ttyACM0 &
sleep 1
nshterm /dev/ttyS0 &
sleep 1
exit

View File

@ -1,100 +0,0 @@
#!nsh
#
# VRBRAIN startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
set HAVE_MICROSD 1
else
echo "[init] no microSD card found"
set HAVE_MICROSD 0
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
if [ $HAVE_MICROSD == 1 ]
then
if [ -f /fs/microsd/bootloader.bin ]
then
bl_update /fs/microsd/bootloader.bin
rm /fs/microsd/bootloader.bin
else
fi
if [ ! -f /fs/microsd/APM/nostart ]
then
if [ -f /etc/init.d/rc.APM ]
then
echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
else
nshterm /dev/ttyACM0 &
fi
else
nshterm /dev/ttyACM0 &
fi
else
if [ -f /etc/init.d/rc.APMNS ]
then
echo "[init] Running rc.APM without SD"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APMNS
else
nshterm /dev/ttyACM0 &
fi
fi

View File

@ -1,252 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# To disable APM startup add a /fs/microsd/APM/nostart file
# check for an old file called APM, caused by
# a bug in an earlier firmware release
if [ -f /fs/microsd/APM ]
then
echo "[APM] APM file found - renaming"
mv /fs/microsd/APM /fs/microsd/APM.old
fi
if [ -f /fs/microsd/APM/nostart ]
then
echo "[APM] APM/nostart found - skipping APM startup"
sh /etc/init.d/rc.error
fi
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APM] binfs already mounted"
else
echo "[APM] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APM] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if rm /fs/microsd/APM/boot.log
then
echo "[APM] Removed old boot.log"
fi
set logfile /fs/microsd/APM/BOOT.LOG
if [ ! -f /bin/ArduPilot ]
then
echo "[APM] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
if mkdir /fs/microsd/APM > /dev/null
then
echo "[APM] Created APM directory"
fi
echo "[APM] Starting UORB"
if uorb start
then
echo "[APM] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting ADC"
if adc start
then
echo "[APM] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting APM sensors"
echo "[APM] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APM] MS5611 onboard started OK"
else
echo "[APM] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MS5611 External EXP"
if ms5611 -X start
then
echo "[APM] MS5611 external EXP started OK"
else
echo "[APM] MS5611 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MS5611 External IMU"
if ms5611 -U start
then
echo "[APM] MS5611 external IMU started OK"
else
echo "[APM] MS5611 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APM] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APM] HMC5883 External GPS calibrate OK"
else
echo "[APM] HMC5883 External GPS calibrate failed"
fi
else
echo "[APM] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 Internal"
if hmc5883 -I start
then
echo "[APM] HMC5883 Internal started OK"
if hmc5883 -I calibrate
then
echo "[APM] HMC5883 Internal calibrate OK"
else
echo "[APM] HMC5883 Internal calibrate failed"
fi
else
echo "[APM] HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5983 External EXP"
if hmc5983 -X start
then
echo "[APM] HMC5983 external EXP started OK"
if hmc5983 -X calibrate
then
echo "[APM] HMC5983 external EXP calibrate OK"
else
echo "[APM] HMC5983 external EXP calibrate failed"
fi
else
echo "[APM] HMC5983 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5983 External IMU"
if hmc5983 -U start
then
echo "[APM] HMC5983 external IMU started OK"
if hmc5983 -U calibrate
then
echo "[APM] HMC5983 external IMU calibrate OK"
else
echo "[APM] HMC5983 external IMU calibrate failed"
fi
else
echo "[APM] HMC5983 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APM] MPU6000 onboard started OK"
else
echo "[APM] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 External EXP"
if mpu6000 -X start
then
echo "[APM] MPU6000 external EXP started OK"
else
echo "[APM] MPU6000 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 External IMU"
if mpu6000 -U start
then
echo "[APM] MPU6000 external IMU started OK"
else
echo "[APM] MPU6000 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APM] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APM] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APM] MTD driver started OK"
else
echo "[APM] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APM] MTD driver readtest OK"
else
echo "[APM] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APM] VROUTPUT driver started OK"
#else
# echo "[APM] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APM] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APM] VRINPUT driver started OK"
#else
# echo "[APM] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APM] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APM] ArduPilot started OK"
else
echo "[APM] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Exiting from nsh shell"
exit
echo "[APM] Script finished"

View File

@ -1,225 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APMNS] binfs already mounted"
else
echo "[APMNS] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APMNS] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if [ ! -f /bin/ArduPilot ]
then
echo "[APMNS] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting UORB"
if uorb start
then
echo "[APMNS] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting ADC"
if adc start
then
echo "[APMNS] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting APM sensors"
echo "[APMNS] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APMNS] MS5611 onboard started OK"
else
echo "[APMNS] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MS5611 External EXP"
if ms5611 -X start
then
echo "[APMNS] MS5611 external EXP started OK"
else
echo "[APMNS] MS5611 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MS5611 External IMU"
if ms5611 -U start
then
echo "[APMNS] MS5611 external IMU started OK"
else
echo "[APMNS] MS5611 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APMNS] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APMNS] HMC5883 External GPS calibrate OK"
else
echo "[APMNS] HMC5883 External GPS calibrate failed"
fi
else
echo "[APMNS] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 Internal"
if hmc5883 -I start
then
echo "[APMNS] HMC5883 Internal started OK"
if hmc5883 -I calibrate
then
echo "[APMNS] HMC5883 Internal calibrate OK"
else
echo "[APMNS] HMC5883 Internal calibrate failed"
fi
else
echo "[APMNS] HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5983 External EXP"
if hmc5983 -X start
then
echo "[APMNS] HMC5983 external EXP started OK"
if hmc5983 -X calibrate
then
echo "[APMNS] HMC5983 external EXP calibrate OK"
else
echo "[APMNS] HMC5983 external EXP calibrate failed"
fi
else
echo "[APMNS] HMC5983 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5983 External IMU"
if hmc5983 -U start
then
echo "[APMNS] HMC5983 external IMU started OK"
if hmc5983 -U calibrate
then
echo "[APMNS] HMC5983 external IMU calibrate OK"
else
echo "[APMNS] HMC5983 external IMU calibrate failed"
fi
else
echo "[APMNS] HMC5983 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APMNS] MPU6000 onboard started OK"
else
echo "[APMNS] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 External EXP"
if mpu6000 -X start
then
echo "[APMNS] MPU6000 external EXP started OK"
else
echo "[APMNS] MPU6000 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 External IMU"
if mpu6000 -U start
then
echo "[APMNS] MPU6000 external IMU started OK"
else
echo "[APMNS] MPU6000 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APMNS] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APMNS] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APMNS] MTD driver started OK"
else
echo "[APMNS] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APMNS] MTD driver readtest OK"
else
echo "[APMNS] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APMNS] VROUTPUT driver started OK"
#else
# echo "[APMNS] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APMNS] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APMNS] VRINPUT driver started OK"
#else
# echo "[APMNS] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APMNS] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APMNS] ArduPilot started OK"
else
echo "[APMNS] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Exiting from nsh shell"
exit
echo "[APMNS] Script finished"

View File

@ -1,7 +0,0 @@
echo "Error in startup"
nshterm /dev/ttyACM0 &
sleep 1
nshterm /dev/ttyS0 &
sleep 1
exit

View File

@ -1,100 +0,0 @@
#!nsh
#
# VRBRAIN startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
set HAVE_MICROSD 1
else
echo "[init] no microSD card found"
set HAVE_MICROSD 0
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
if [ $HAVE_MICROSD == 1 ]
then
if [ -f /fs/microsd/bootloader.bin ]
then
bl_update /fs/microsd/bootloader.bin
rm /fs/microsd/bootloader.bin
else
fi
if [ ! -f /fs/microsd/APM/nostart ]
then
if [ -f /etc/init.d/rc.APM ]
then
echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
else
nshterm /dev/ttyACM0 &
fi
else
nshterm /dev/ttyACM0 &
fi
else
if [ -f /etc/init.d/rc.APMNS ]
then
echo "[init] Running rc.APM without SD"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APMNS
else
nshterm /dev/ttyACM0 &
fi
fi

View File

@ -1,252 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# To disable APM startup add a /fs/microsd/APM/nostart file
# check for an old file called APM, caused by
# a bug in an earlier firmware release
if [ -f /fs/microsd/APM ]
then
echo "[APM] APM file found - renaming"
mv /fs/microsd/APM /fs/microsd/APM.old
fi
if [ -f /fs/microsd/APM/nostart ]
then
echo "[APM] APM/nostart found - skipping APM startup"
sh /etc/init.d/rc.error
fi
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APM] binfs already mounted"
else
echo "[APM] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APM] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if rm /fs/microsd/APM/boot.log
then
echo "[APM] Removed old boot.log"
fi
set logfile /fs/microsd/APM/BOOT.LOG
if [ ! -f /bin/ArduPilot ]
then
echo "[APM] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
if mkdir /fs/microsd/APM > /dev/null
then
echo "[APM] Created APM directory"
fi
echo "[APM] Starting UORB"
if uorb start
then
echo "[APM] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting ADC"
if adc start
then
echo "[APM] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting APM sensors"
echo "[APM] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APM] MS5611 onboard started OK"
else
echo "[APM] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MS5611 External EXP"
if ms5611 -X start
then
echo "[APM] MS5611 external EXP started OK"
else
echo "[APM] MS5611 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MS5611 External IMU"
if ms5611 -U start
then
echo "[APM] MS5611 external IMU started OK"
else
echo "[APM] MS5611 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APM] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APM] HMC5883 External GPS calibrate OK"
else
echo "[APM] HMC5883 External GPS calibrate failed"
fi
else
echo "[APM] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 Internal"
if hmc5883 -I start
then
echo "[APM] HMC5883 Internal started OK"
if hmc5883 -I calibrate
then
echo "[APM] HMC5883 Internal calibrate OK"
else
echo "[APM] HMC5883 Internal calibrate failed"
fi
else
echo "[APM] HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5983 External EXP"
if hmc5983 -X start
then
echo "[APM] HMC5983 external EXP started OK"
if hmc5983 -X calibrate
then
echo "[APM] HMC5983 external EXP calibrate OK"
else
echo "[APM] HMC5983 external EXP calibrate failed"
fi
else
echo "[APM] HMC5983 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5983 External IMU"
if hmc5983 -U start
then
echo "[APM] HMC5983 external IMU started OK"
if hmc5983 -U calibrate
then
echo "[APM] HMC5983 external IMU calibrate OK"
else
echo "[APM] HMC5983 external IMU calibrate failed"
fi
else
echo "[APM] HMC5983 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APM] MPU6000 onboard started OK"
else
echo "[APM] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 External EXP"
if mpu6000 -X start
then
echo "[APM] MPU6000 external EXP started OK"
else
echo "[APM] MPU6000 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 External IMU"
if mpu6000 -U start
then
echo "[APM] MPU6000 external IMU started OK"
else
echo "[APM] MPU6000 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APM] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APM] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APM] MTD driver started OK"
else
echo "[APM] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APM] MTD driver readtest OK"
else
echo "[APM] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APM] VROUTPUT driver started OK"
#else
# echo "[APM] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APM] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APM] VRINPUT driver started OK"
#else
# echo "[APM] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APM] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APM] ArduPilot started OK"
else
echo "[APM] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Exiting from nsh shell"
exit
echo "[APM] Script finished"

View File

@ -1,225 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APMNS] binfs already mounted"
else
echo "[APMNS] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APMNS] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if [ ! -f /bin/ArduPilot ]
then
echo "[APMNS] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting UORB"
if uorb start
then
echo "[APMNS] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting ADC"
if adc start
then
echo "[APMNS] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting APM sensors"
echo "[APMNS] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APMNS] MS5611 onboard started OK"
else
echo "[APMNS] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MS5611 External EXP"
if ms5611 -X start
then
echo "[APMNS] MS5611 external EXP started OK"
else
echo "[APMNS] MS5611 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MS5611 External IMU"
if ms5611 -U start
then
echo "[APMNS] MS5611 external IMU started OK"
else
echo "[APMNS] MS5611 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APMNS] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APMNS] HMC5883 External GPS calibrate OK"
else
echo "[APMNS] HMC5883 External GPS calibrate failed"
fi
else
echo "[APMNS] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 Internal"
if hmc5883 -I start
then
echo "[APMNS] HMC5883 Internal started OK"
if hmc5883 -I calibrate
then
echo "[APMNS] HMC5883 Internal calibrate OK"
else
echo "[APMNS] HMC5883 Internal calibrate failed"
fi
else
echo "[APMNS] HMC5883 Internal start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5983 External EXP"
if hmc5983 -X start
then
echo "[APMNS] HMC5983 external EXP started OK"
if hmc5983 -X calibrate
then
echo "[APMNS] HMC5983 external EXP calibrate OK"
else
echo "[APMNS] HMC5983 external EXP calibrate failed"
fi
else
echo "[APMNS] HMC5983 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5983 External IMU"
if hmc5983 -U start
then
echo "[APMNS] HMC5983 external IMU started OK"
if hmc5983 -U calibrate
then
echo "[APMNS] HMC5983 external IMU calibrate OK"
else
echo "[APMNS] HMC5983 external IMU calibrate failed"
fi
else
echo "[APMNS] HMC5983 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APMNS] MPU6000 onboard started OK"
else
echo "[APMNS] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 External EXP"
if mpu6000 -X start
then
echo "[APMNS] MPU6000 external EXP started OK"
else
echo "[APMNS] MPU6000 external EXP start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 External IMU"
if mpu6000 -U start
then
echo "[APMNS] MPU6000 external IMU started OK"
else
echo "[APMNS] MPU6000 external IMU start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APMNS] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APMNS] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APMNS] MTD driver started OK"
else
echo "[APMNS] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APMNS] MTD driver readtest OK"
else
echo "[APMNS] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APMNS] VROUTPUT driver started OK"
#else
# echo "[APMNS] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APMNS] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APMNS] VRINPUT driver started OK"
#else
# echo "[APMNS] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APMNS] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APMNS] ArduPilot started OK"
else
echo "[APMNS] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Exiting from nsh shell"
exit
echo "[APMNS] Script finished"

View File

@ -1,7 +0,0 @@
echo "Error in startup"
nshterm /dev/ttyACM0 &
sleep 1
nshterm /dev/ttyS0 &
sleep 1
exit

View File

@ -1,100 +0,0 @@
#!nsh
#
# VRBRAIN startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
set HAVE_MICROSD 1
else
echo "[init] no microSD card found"
set HAVE_MICROSD 0
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
if [ $HAVE_MICROSD == 1 ]
then
if [ -f /fs/microsd/bootloader.bin ]
then
bl_update /fs/microsd/bootloader.bin
rm /fs/microsd/bootloader.bin
else
fi
if [ ! -f /fs/microsd/APM/nostart ]
then
if [ -f /etc/init.d/rc.APM ]
then
echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
else
nshterm /dev/ttyACM0 &
fi
else
nshterm /dev/ttyACM0 &
fi
else
if [ -f /etc/init.d/rc.APMNS ]
then
echo "[init] Running rc.APM without SD"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APMNS
else
nshterm /dev/ttyACM0 &
fi
fi

View File

@ -1,171 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# To disable APM startup add a /fs/microsd/APM/nostart file
# check for an old file called APM, caused by
# a bug in an earlier firmware release
if [ -f /fs/microsd/APM ]
then
echo "[APM] APM file found - renaming"
mv /fs/microsd/APM /fs/microsd/APM.old
fi
if [ -f /fs/microsd/APM/nostart ]
then
echo "[APM] APM/nostart found - skipping APM startup"
sh /etc/init.d/rc.error
fi
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APM] binfs already mounted"
else
echo "[APM] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APM] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if rm /fs/microsd/APM/boot.log
then
echo "[APM] Removed old boot.log"
fi
set logfile /fs/microsd/APM/BOOT.LOG
if [ ! -f /bin/ArduPilot ]
then
echo "[APM] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
if mkdir /fs/microsd/APM > /dev/null
then
echo "[APM] Created APM directory"
fi
echo "[APM] Starting UORB"
if uorb start
then
echo "[APM] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting ADC"
if adc start
then
echo "[APM] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting APM sensors"
echo "[APM] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APM] MS5611 onboard started OK"
else
echo "[APM] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APM] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APM] HMC5883 External GPS calibrate OK"
else
echo "[APM] HMC5883 External GPS calibrate failed"
fi
else
echo "[APM] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APM] MPU6000 onboard started OK"
else
echo "[APM] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APM] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APM] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APM] MTD driver started OK"
else
echo "[APM] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APM] MTD driver readtest OK"
else
echo "[APM] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APM] VROUTPUT driver started OK"
#else
# echo "[APM] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APM] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APM] VRINPUT driver started OK"
#else
# echo "[APM] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APM] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APM] ArduPilot started OK"
else
echo "[APM] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Exiting from nsh shell"
exit
echo "[APM] Script finished"

View File

@ -1,144 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APMNS] binfs already mounted"
else
echo "[APMNS] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APMNS] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if [ ! -f /bin/ArduPilot ]
then
echo "[APMNS] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting UORB"
if uorb start
then
echo "[APMNS] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting ADC"
if adc start
then
echo "[APMNS] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting APM sensors"
echo "[APMNS] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APMNS] MS5611 onboard started OK"
else
echo "[APMNS] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APMNS] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APMNS] HMC5883 External GPS calibrate OK"
else
echo "[APMNS] HMC5883 External GPS calibrate failed"
fi
else
echo "[APMNS] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APMNS] MPU6000 onboard started OK"
else
echo "[APMNS] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APMNS] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APMNS] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APMNS] MTD driver started OK"
else
echo "[APMNS] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APMNS] MTD driver readtest OK"
else
echo "[APMNS] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APMNS] VROUTPUT driver started OK"
#else
# echo "[APMNS] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APMNS] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APMNS] VRINPUT driver started OK"
#else
# echo "[APMNS] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APMNS] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APMNS] ArduPilot started OK"
else
echo "[APMNS] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Exiting from nsh shell"
exit
echo "[APMNS] Script finished"

View File

@ -1,7 +0,0 @@
echo "Error in startup"
nshterm /dev/ttyACM0 &
sleep 1
nshterm /dev/ttyS0 &
sleep 1
exit

View File

@ -1,100 +0,0 @@
#!nsh
#
# VRBRAIN startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
set HAVE_MICROSD 1
else
echo "[init] no microSD card found"
set HAVE_MICROSD 0
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
if [ $HAVE_MICROSD == 1 ]
then
if [ -f /fs/microsd/bootloader.bin ]
then
bl_update /fs/microsd/bootloader.bin
rm /fs/microsd/bootloader.bin
else
fi
if [ ! -f /fs/microsd/APM/nostart ]
then
if [ -f /etc/init.d/rc.APM ]
then
echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
else
nshterm /dev/ttyACM0 &
fi
else
nshterm /dev/ttyACM0 &
fi
else
if [ -f /etc/init.d/rc.APMNS ]
then
echo "[init] Running rc.APM without SD"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APMNS
else
nshterm /dev/ttyACM0 &
fi
fi

View File

@ -1,171 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# To disable APM startup add a /fs/microsd/APM/nostart file
# check for an old file called APM, caused by
# a bug in an earlier firmware release
if [ -f /fs/microsd/APM ]
then
echo "[APM] APM file found - renaming"
mv /fs/microsd/APM /fs/microsd/APM.old
fi
if [ -f /fs/microsd/APM/nostart ]
then
echo "[APM] APM/nostart found - skipping APM startup"
sh /etc/init.d/rc.error
fi
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APM] binfs already mounted"
else
echo "[APM] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APM] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if rm /fs/microsd/APM/boot.log
then
echo "[APM] Removed old boot.log"
fi
set logfile /fs/microsd/APM/BOOT.LOG
if [ ! -f /bin/ArduPilot ]
then
echo "[APM] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
if mkdir /fs/microsd/APM > /dev/null
then
echo "[APM] Created APM directory"
fi
echo "[APM] Starting UORB"
if uorb start
then
echo "[APM] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting ADC"
if adc start
then
echo "[APM] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APM] Starting APM sensors"
echo "[APM] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APM] MS5611 onboard started OK"
else
echo "[APM] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APM] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APM] HMC5883 External GPS calibrate OK"
else
echo "[APM] HMC5883 External GPS calibrate failed"
fi
else
echo "[APM] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APM] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APM] MPU6000 onboard started OK"
else
echo "[APM] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APM] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APM] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APM] MTD driver started OK"
else
echo "[APM] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APM] MTD driver readtest OK"
else
echo "[APM] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APM] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APM] VROUTPUT driver started OK"
#else
# echo "[APM] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APM] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APM] VRINPUT driver started OK"
#else
# echo "[APM] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APM] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APM] ArduPilot started OK"
else
echo "[APM] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APM] Exiting from nsh shell"
exit
echo "[APM] Script finished"

View File

@ -1,144 +0,0 @@
#!nsh
# APM startup script for NuttX on VRBRAIN
# mount binfs so we can find the built-in apps
if [ -f /bin/reboot ]
then
echo "[APMNS] binfs already mounted"
else
echo "[APMNS] Mounting binfs"
if mount -t binfs /dev/null /bin
then
echo "[APMNS] binfs mounted OK"
else
sh /etc/init.d/rc.error
fi
fi
if [ ! -f /bin/ArduPilot ]
then
echo "[APMNS] /bin/ArduPilot not found"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting UORB"
if uorb start
then
echo "[APMNS] UORB started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting ADC"
if adc start
then
echo "[APMNS] ADC started OK"
else
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting APM sensors"
echo "[APMNS] Starting MS5611 Internal"
if ms5611 -I start
then
echo "[APMNS] MS5611 onboard started OK"
else
echo "[APMNS] MS5611 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting HMC5883 External GPS"
if hmc5883 -X start
then
echo "[APMNS] HMC5883 External GPS started OK"
if hmc5883 -X calibrate
then
echo "[APMNS] HMC5883 External GPS calibrate OK"
else
echo "[APMNS] HMC5883 External GPS calibrate failed"
fi
else
echo "[APMNS] HMC5883 External GPS start failed"
# sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MPU6000 Internal"
if mpu6000 -I start
then
echo "[APMNS] MPU6000 onboard started OK"
else
echo "[APMNS] MPU6000 onboard start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting MEAS I2C Airspeed"
if meas_airspeed start
then
echo "Found MEAS airspeed sensor"
fi
echo "[APMNS] Starting MB12XX Range Finder Sensor"
if mb12xx start
then
echo "Found mb12xx sensor"
fi
echo "[APMNS] Starting MTD driver"
if mtd start /fs/mtd
then
echo "[APMNS] MTD driver started OK"
else
echo "[APMNS] MTD driver start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] MTD driver read test"
if mtd readtest /fs/mtd
then
echo "[APMNS] MTD driver readtest OK"
else
echo "[APMNS] MTD driver failed to read"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Starting VROUTPUT driver"
vroutput mode_pwm
#if vroutput mode_pwm
#then
# echo "[APMNS] VROUTPUT driver started OK"
#else
# echo "[APMNS] VROUTPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
echo "[APMNS] Starting VRINPUT driver"
vrinput start
#if vrinput start
#then
# echo "[APMNS] VRINPUT driver started OK"
#else
# echo "[APMNS] VRINPUT driver start failed"
# sh /etc/init.d/rc.error
#fi
set sketch NONE
set deviceA /dev/ttyACM0
set deviceC /dev/ttyS2
echo "[APMNS] Starting ArduPilot"
#if ArduPilot -d $deviceA -d2 $deviceC start
if ArduPilot start
then
echo "[APMNS] ArduPilot started OK"
else
echo "[APMNS] ArduPilot start failed"
sh /etc/init.d/rc.error
fi
echo "[APMNS] Exiting from nsh shell"
exit
echo "[APMNS] Script finished"

View File

@ -1,7 +0,0 @@
echo "Error in startup"
nshterm /dev/ttyACM0 &
sleep 1
nshterm /dev/ttyS0 &
sleep 1
exit

View File

@ -1,100 +0,0 @@
#!nsh
#
# VRBRAIN startup script.
#
# This script is responsible for:
#
# - mounting the microSD card (if present)
# - running the user startup script from the microSD card (if present)
# - detecting the configuration of the system and picking a suitable
# startup script to continue with
#
# Note: DO NOT add configuration-specific commands to this script;
# add them to the per-configuration scripts instead.
#
#
# Default to auto-start mode. An init script on the microSD card
# can change this to prevent automatic startup of the flight script.
#
set MODE autostart
set USB autoconnect
#
# Try to mount the microSD card.
#
echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
set HAVE_MICROSD 1
else
echo "[init] no microSD card found"
set HAVE_MICROSD 0
fi
#
# Look for an init script on the microSD card.
#
# To prevent automatic startup in the current flight mode,
# the script should set MODE to some other value.
#
if [ -f /fs/microsd/etc/rc ]
then
echo "[init] reading /fs/microsd/etc/rc"
sh /fs/microsd/etc/rc
fi
# Also consider rc.txt files
if [ -f /fs/microsd/etc/rc.txt ]
then
echo "[init] reading /fs/microsd/etc/rc.txt"
sh /fs/microsd/etc/rc.txt
fi
#
# Check for USB host
#
if [ $USB != autoconnect ]
then
echo "[init] not connecting USB"
else
if sercon
then
echo "[init] USB interface connected"
else
echo "[init] No USB connected"
fi
fi
if [ $HAVE_MICROSD == 1 ]
then
if [ -f /fs/microsd/bootloader.bin ]
then
bl_update /fs/microsd/bootloader.bin
rm /fs/microsd/bootloader.bin
else
fi
if [ ! -f /fs/microsd/APM/nostart ]
then
if [ -f /etc/init.d/rc.APM ]
then
echo "[init] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
else
nshterm /dev/ttyACM0 &
fi
else
nshterm /dev/ttyACM0 &
fi
else
if [ -f /etc/init.d/rc.APMNS ]
then
echo "[init] Running rc.APM without SD"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APMNS
else
nshterm /dev/ttyACM0 &
fi
fi

View File

@ -0,0 +1,5 @@
These tools are from the ros project. You can find the master sources
here:
http://github.com/ros/gencpp
http://github.com/ros/genmsg

3
mk/VRBRAIN/Tools/gencpp/.gitignore vendored Normal file
View File

@ -0,0 +1,3 @@
*.pyc
._*
*~

View File

@ -0,0 +1,42 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package gencpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.5.2 (2014-05-07)
------------------
* add architecture_independent flag in package.xml (`#19 <https://github.com/ros/gencpp/issues/19>`_)
0.5.1 (2014-02-24)
------------------
* use catkin_install_python() to install Python scripts (`#18 <https://github.com/ros/gencpp/issues/18>`_)
* add 'u' suffix to unsigned enum values to avoid compiler warning (`#16 <https://github.com/ros/gencpp/issues/16>`_)
0.5.0 (2014-01-29)
------------------
* remove __connection_header from message template (`#3 <https://github.com/ros/gencpp/issues/3>`_)
0.4.16 (2014-01-27)
-------------------
* fix warning about empty message definition (`ros/ros_comm#344 <https://github.com/ros/ros_comm/issues/344>`_)
0.4.15 (2014-01-07)
-------------------
* python 3 compatibility
* fix generated code of message definition with windows line endings (`#6 <https://github.com/ros/gencpp/issues/6>`_)
0.4.14 (2013-08-21)
-------------------
* make gencpp relocatable (`ros/catkin#490 <https://github.com/ros/catkin/issues/490>`_)
0.4.13 (2013-06-18)
-------------------
* update message targets to depend on template
* update msg template to generate empty functions without warnings about unused variables (`#4 <https://github.com/ros/gencpp/issues/4>`_)
0.4.12 (2013-03-08)
-------------------
* fix handling spaces in folder names (`ros/catkin#375 <https://github.com/ros/catkin/issues/375>`_)
0.4.11 (2012-12-21)
-------------------
* first public release for Groovy

View File

@ -0,0 +1,16 @@
cmake_minimum_required(VERSION 2.8.3)
project(gencpp)
find_package(catkin REQUIRED COMPONENTS genmsg)
catkin_package(
CATKIN_DEPENDS genmsg
CFG_EXTRAS gencpp-extras.cmake
)
add_subdirectory(scripts)
file(WRITE ${CATKIN_DEVEL_PREFIX}/${GENMSG_LANGS_DESTINATION}/gencpp "C++")
install(FILES ${CATKIN_DEVEL_PREFIX}/${GENMSG_LANGS_DESTINATION}/gencpp
DESTINATION ${GENMSG_LANGS_DESTINATION})
catkin_python_setup()

View File

@ -0,0 +1,57 @@
@[if DEVELSPACE]@
# bin and template dir variables in develspace
set(GENCPP_BIN "@(CMAKE_CURRENT_SOURCE_DIR)/scripts/gen_cpp.py")
set(GENCPP_TEMPLATE_DIR "@(CMAKE_CURRENT_SOURCE_DIR)/scripts")
@[else]@
# bin and template dir variables in installspace
set(GENCPP_BIN "${gencpp_DIR}/../../../@(CATKIN_PACKAGE_BIN_DESTINATION)/gen_cpp.py")
set(GENCPP_TEMPLATE_DIR "${gencpp_DIR}/..")
@[end if]@
# Generate .msg->.h for cpp
# The generated .h files should be added ALL_GEN_OUTPUT_FILES_cpp
macro(_generate_msg_cpp ARG_PKG ARG_MSG ARG_IFLAGS ARG_MSG_DEPS ARG_GEN_OUTPUT_DIR)
file(MAKE_DIRECTORY ${ARG_GEN_OUTPUT_DIR})
#Create input and output filenames
get_filename_component(MSG_NAME ${ARG_MSG} NAME)
get_filename_component(MSG_SHORT_NAME ${ARG_MSG} NAME_WE)
set(MSG_GENERATED_NAME ${MSG_SHORT_NAME}.h)
set(GEN_OUTPUT_FILE ${ARG_GEN_OUTPUT_DIR}/${MSG_GENERATED_NAME})
assert(CATKIN_ENV)
add_custom_command(OUTPUT ${GEN_OUTPUT_FILE}
DEPENDS ${GENCPP_BIN} ${ARG_MSG} ${ARG_MSG_DEPS} "${GENCPP_TEMPLATE_DIR}/msg.h.template" ${ARGN}
COMMAND ${CATKIN_ENV} ${PYTHON_EXECUTABLE} ${GENCPP_BIN} ${ARG_MSG}
${ARG_IFLAGS}
-p ${ARG_PKG}
-o ${ARG_GEN_OUTPUT_DIR}
-e ${GENCPP_TEMPLATE_DIR}
COMMENT "Generating C++ code from ${ARG_PKG}/${MSG_NAME}"
)
list(APPEND ALL_GEN_OUTPUT_FILES_cpp ${GEN_OUTPUT_FILE})
gencpp_append_include_dirs()
endmacro()
#gencpp uses the same program to generate srv and msg files, so call the same macro
macro(_generate_srv_cpp ARG_PKG ARG_SRV ARG_IFLAGS ARG_MSG_DEPS ARG_GEN_OUTPUT_DIR)
_generate_msg_cpp(${ARG_PKG} ${ARG_SRV} "${ARG_IFLAGS}" "${ARG_MSG_DEPS}" ${ARG_GEN_OUTPUT_DIR} "${GENCPP_TEMPLATE_DIR}/srv.h.template")
endmacro()
macro(_generate_module_cpp)
# the macros, they do nothing
endmacro()
set(gencpp_INSTALL_DIR include)
macro(gencpp_append_include_dirs)
if(NOT gencpp_APPENDED_INCLUDE_DIRS)
# make sure we can find generated messages and that they overlay all other includes
include_directories(BEFORE ${CATKIN_DEVEL_PREFIX}/${gencpp_INSTALL_DIR})
# pass the include directory to catkin_package()
list(APPEND ${PROJECT_NAME}_INCLUDE_DIRS ${CATKIN_DEVEL_PREFIX}/${gencpp_INSTALL_DIR})
set(gencpp_APPENDED_INCLUDE_DIRS TRUE)
endif()
endmacro()

View File

@ -0,0 +1,27 @@
<?xml version="1.0"?>
<package>
<name>gencpp</name>
<version>0.5.2</version>
<description>C++ ROS message and service generators.</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<license>BSD</license>
<url type="bugtracker">https://github.com/ros/gencpp/issues</url>
<url type="repository">https://github.com/ros/gencpp</url>
<author>Josh Faust</author>
<author>Troy Straszheim</author>
<author>Morgen Kjaergaard</author>
<buildtool_depend version_gte="0.5.78">catkin</buildtool_depend>
<build_depend>genmsg</build_depend>
<run_depend>genmsg</run_depend>
<export>
<message_generator>cpp</message_generator>
<rosdoc config="rosdoc.yaml"/>
<architecture_independent/>
</export>
</package>

View File

@ -0,0 +1,2 @@
- builder: sphinx
sphinx_root_dir: doc

View File

@ -0,0 +1,7 @@
install(
FILES msg.h.template srv.h.template
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
catkin_install_python(
PROGRAMS gen_cpp.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

View File

@ -0,0 +1,50 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2009, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
#
## ROS message source code generation for C++
##
## Converts ROS .msg files in a package into C++ source code implementations.
import sys
import os
import genmsg.template_tools
msg_template_map = { 'msg.h.template':'@NAME@.h' }
srv_template_map = { 'srv.h.template':'@NAME@.h' }
if __name__ == "__main__":
genmsg.template_tools.generate_from_command_line_options(sys.argv,
msg_template_map,
srv_template_map)

View File

@ -0,0 +1,309 @@
@###############################################
@#
@# ROS message source code generation for C++
@#
@# EmPy template for generating <msg>.h files
@#
@###############################################
@# Start of Template
@#
@# Context:
@# - file_name_in (String) Source file
@# - spec (msggen.MsgSpec) Parsed specification of the .msg file
@# - md5sum (String) MD5Sum of the .msg specification
@###############################################
/* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * 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.
* * Neither the name of Willow Garage, Inc. 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 OWNER 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.
*
* Auto-generated by genmsg_cpp from file @file_name_in
*
*/
@{
import genmsg.msgs
import gencpp
cpp_namespace = '::%s::'%(spec.package) # TODO handle nested namespace
cpp_class = '%s_'%spec.short_name
cpp_full_name = '%s%s'%(cpp_namespace,cpp_class)
cpp_full_name_with_alloc = '%s<ContainerAllocator>'%(cpp_full_name)
cpp_msg_definition = gencpp.escape_message_definition(msg_definition)
}@
#ifndef @(spec.package.upper())_MESSAGE_@(spec.short_name.upper())_H
#define @(spec.package.upper())_MESSAGE_@(spec.short_name.upper())_H
@##############################
@# Generic Includes
@##############################
#include <string>
#include <vector>
#include <map>
#include <ros/types.h>
#include <ros/serialization.h>
#include <ros/builtin_message_traits.h>
#include <ros/message_operations.h>
@##############################
@# Includes for dependencies
@##############################
@{
for field in spec.parsed_fields():
if (not field.is_builtin):
if (field.is_header):
print('#include <std_msgs/Header.h>')
else:
(package, name) = genmsg.names.package_resource_name(field.base_type)
package = package or spec.package # convert '' to package
print('#include <%s/%s.h>'%(package, name))
}@
namespace @(spec.package)
{
template <class ContainerAllocator>
struct @(spec.short_name)_
{
typedef @(spec.short_name)_<ContainerAllocator> Type;
@# constructors (with and without allocator)
@[for (alloc_type,alloc_name) in [['',''],['const ContainerAllocator& ','_alloc']]]@
@(spec.short_name)_(@(alloc_type+alloc_name))
@# Write initializer list
@('\n '.join(gencpp.generate_initializer_list(spec, alloc_name != '' )))@
{
@# Fixed length arrays
@('\n '.join(gencpp.generate_fixed_length_assigns(spec, alloc_name != '', '%s::'%(spec.package))))@
}
@[end for]
@[for field in spec.parsed_fields()]
@{cpp_type = gencpp.msg_type_to_cpp(field.type)}@
typedef @(cpp_type) _@(field.name)_type;
_@(field.name)_type @(field.name);
@[end for]
@# Constants
@[for constant in spec.constants]@
@[if (constant.type in ['byte', 'int8', 'int16', 'int32', 'int64', 'char'])]@
enum { @(constant.name) = @(int(constant.val)) };
@[elif (constant.type in ['uint8', 'uint16', 'uint32', 'uint64'])]@
enum { @(constant.name) = @(int(constant.val))u };
@[else]@
static const @(gencpp.msg_type_to_cpp(constant.type)) @(constant.name);
@[end if]@
@[end for]
@# Shared pointer typedefs
typedef boost::shared_ptr< @(cpp_full_name)<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< @(cpp_full_name)<ContainerAllocator> const> ConstPtr;
}; // struct @(cpp_class)
@# Typedef of template instance using std::allocator
typedef @(cpp_full_name)<std::allocator<void> > @(spec.short_name);
@# Shared pointer typedefs
typedef boost::shared_ptr< @(cpp_namespace+spec.short_name) > @(spec.short_name)Ptr;
typedef boost::shared_ptr< @(cpp_namespace+spec.short_name) const> @(spec.short_name)ConstPtr;
// constants requiring out of line definition
@[for c in spec.constants]
@[if c.type not in ['byte', 'int8', 'int16', 'int32', 'int64', 'char', 'uint8', 'uint16', 'uint32', 'uint64']]
template<typename ContainerAllocator> const @(gencpp.msg_type_to_cpp(c.type))
@(spec.short_name)_<ContainerAllocator>::@(c.name) =
@[if c.type == 'string']
"@(gencpp.escape_string(c.val))"
@[elif c.type == 'bool']
@(int(c.val))
@[else]
@c.val
@[end if]
;
@[end if]
@[end for]
@# Printer
template<typename ContainerAllocator>
std::ostream& operator<<(std::ostream& s, const @(cpp_full_name_with_alloc) & v)
{
ros::message_operations::Printer< @(cpp_full_name_with_alloc) >::stream(s, "", v);
return s;
}
@# End of namespace
} // namespace @(spec.package)
@# Message Traits
namespace ros
{
namespace message_traits
{
@{
bool_traits = dict(IsMessage=True,
IsFixedSize=gencpp.is_fixed_length(spec, msg_context, search_path),
HasHeader=spec.has_header(),
)
def booltotype(b):
return "TrueType" if b else "FalseType"
}
// BOOLTRAITS @bool_traits
// @search_path
@# TODO
// !!!!!!!!!!! @(dir(spec))
@#if spec.is_fixed_length():
@# traits = traits.append('IsFixedSize')
@#template <class ContainerAllocator>
@#struct IsFixedSize<@(cpp_full_name_with_alloc) >:: @(dir(spec)) ? "TrueType" ! "FalseType") { };
@#template <class ContainerAllocator>
@#struct IsFixedSize<@(cpp_full_name_with_alloc) const >:: @(dir(spec)) ? "TrueType" ! "FalseType") { };
@# Binary traits
@[for k, v in bool_traits.items()]@
template <class ContainerAllocator>
struct @(k)< @(cpp_full_name_with_alloc) >
: @(booltotype(v))
{ };
template <class ContainerAllocator>
struct @(k)< @(cpp_full_name_with_alloc) const>
: @(booltotype(v))
{ };
@[end for]@
@# String traits
@[for trait_class,trait_value in [['MD5Sum', md5sum], ['DataType', spec.full_name], ['Definition', cpp_msg_definition]]]@
template<class ContainerAllocator>
struct @(trait_class)< @(cpp_full_name_with_alloc) >
{
static const char* value()
{
return "@(trait_value)";
}
static const char* value(const @(cpp_full_name_with_alloc)&) { return value(); }
@{
if trait_class == 'MD5Sum':
iter_count = int(len(trait_value) / 16)
for i in range(0, iter_count):
start = i*16
print(' static const uint64_t static_value%s = 0x%sULL;'%((i+1), trait_value[start:start+16]))
}@
};
@[end for]@
@# End of traits
} // namespace message_traits
} // namespace ros
@# Serialization
namespace ros
{
namespace serialization
{
template<class ContainerAllocator> struct Serializer< @(cpp_full_name_with_alloc) >
{
@[if spec.parsed_fields()]@
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
{
@[for field in spec.parsed_fields()]@
stream.next(m.@(field.name));
@[end for]@
}
@[else]@
template<typename Stream, typename T> inline static void allInOne(Stream&, T)
{}
@[end if]@
ROS_DECLARE_ALLINONE_SERIALIZER;
}; // struct @(cpp_class)
} // namespace serialization
} // namespace ros
@# Message Operations
namespace ros
{
namespace message_operations
{
@# Printer operation
template<class ContainerAllocator>
struct Printer< @(cpp_full_name_with_alloc) >
{
@[if spec.parsed_fields()]@
template<typename Stream> static void stream(Stream& s, const std::string& indent, const @(cpp_full_name_with_alloc)& v)
{
@# todo, change this stuff below into proper EmPy syntax
@{
for field in spec.parsed_fields():
cpp_type = gencpp.msg_type_to_cpp(field.base_type)
if (field.is_array):
print(' s << indent << "%s[]" << std::endl;'%(field.name))
print(' for (size_t i = 0; i < v.%s.size(); ++i)'%(field.name))
print(' {')
print(' s << indent << " %s[" << i << "]: ";'%(field.name))
indent_increment = ' '
if (not field.is_builtin):
print(' s << std::endl;')
print(' s << indent;')
indent_increment = ' ';
print(' Printer<%s>::stream(s, indent + "%s", v.%s[i]);'%(cpp_type, indent_increment, field.name))
print(' }')
else:
print(' s << indent << "%s: ";'%(field.name))
indent_increment = ' '
if (not field.is_builtin or field.is_array):
print(' s << std::endl;')
print(' Printer<%s>::stream(s, indent + "%s", v.%s);'%(cpp_type, indent_increment, field.name))
}@
}
@[else]@
template<typename Stream> static void stream(Stream&, const std::string&, const @(cpp_full_name_with_alloc)&)
{}
@[end if]@
};
} // namespace message_operations
} // namespace ros
#endif // @(spec.package.upper())_MESSAGE_@(spec.short_name.upper())_H

View File

@ -0,0 +1,174 @@
@###############################################
@#
@# ROS message source code generation for C++
@#
@# EmPy template for generating <msg>.h files
@#
@###############################################
@# Start of Template
@#
@# Context:
@# - file_name_in (String) Source .srv file
@# - spec (msggen.SrvSpec) Parsed specification of the .srv file
@# - md5sum (String) MD5Sum of the .srv specification
@###############################################
/* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * 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.
* * Neither the name of Willow Garage, Inc. 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 OWNER 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.
*
* Auto-generated by gensrv_cpp from file @file_name_in
*
*/
@{
cpp_namespace = '::'+spec.package+'::' # TODO handle nested namespace
cpp_class = spec.short_name
cpp_full_name = cpp_namespace+cpp_class
}@
#ifndef @(spec.package.upper())_MESSAGE_@(spec.short_name.upper())_H
#define @(spec.package.upper())_MESSAGE_@(spec.short_name.upper())_H
#include <ros/service_traits.h>
@###############################################
@# Generate Request and Response Messages
@###############################################
#include <@(spec.package)/@(spec.short_name)Request.h>
#include <@(spec.package)/@(spec.short_name)Response.h>
@###############################################
@# Service Struct
@###############################################
namespace @(spec.package)
{
struct @(spec.short_name)
{
typedef @(spec.request.short_name) Request;
typedef @(spec.response.short_name) Response;
Request request;
Response response;
typedef Request RequestType;
typedef Response ResponseType;
}; // struct @(spec.short_name)
} // namespace @(spec.package)
@###############################################
@# Service-Traits
@###############################################
namespace ros
{
namespace service_traits
{
@[for trait_class,trait_value in [['MD5Sum', md5sum], ['DataType', spec.full_name]] ]
template<>
struct @trait_class< @cpp_full_name > {
static const char* value()
{
return "@(trait_value)";
}
static const char* value(const @(cpp_full_name)&) { return value(); }
};
@[end for]
// service_traits::MD5Sum< @(cpp_full_name)Request> should match
// service_traits::MD5Sum< @cpp_full_name >
template<>
struct MD5Sum< @(cpp_full_name)Request>
{
static const char* value()
{
return MD5Sum< @cpp_full_name >::value();
}
static const char* value(const @(cpp_full_name)Request&)
{
return value();
}
};
// service_traits::DataType< @(cpp_full_name)Request> should match
// service_traits::DataType< @cpp_full_name >
template<>
struct DataType< @(cpp_full_name)Request>
{
static const char* value()
{
return DataType< @cpp_full_name >::value();
}
static const char* value(const @(cpp_full_name)Request&)
{
return value();
}
};
// service_traits::MD5Sum< @(cpp_full_name)Response> should match
// service_traits::MD5Sum< @cpp_full_name >
template<>
struct MD5Sum< @(cpp_full_name)Response>
{
static const char* value()
{
return MD5Sum< @cpp_full_name >::value();
}
static const char* value(const @(cpp_full_name)Response&)
{
return value();
}
};
// service_traits::DataType< @(cpp_full_name)Response> should match
// service_traits::DataType< @cpp_full_name >
template<>
struct DataType< @(cpp_full_name)Response>
{
static const char* value()
{
return DataType< @cpp_full_name >::value();
}
static const char* value(const @(cpp_full_name)Response&)
{
return value();
}
};
} // namespace service_traits
} // namespace ros
#endif // @(spec.package.upper())_MESSAGE_@(spec.short_name.upper())_H

View File

@ -0,0 +1,12 @@
#!/usr/bin/env python
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
d = generate_distutils_setup(
packages=['gencpp'],
package_dir={'': 'src'},
requires=['genmsg']
)
setup(**d)

View File

@ -0,0 +1,254 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
import genmsg.msgs
try:
from cStringIO import StringIO #Python 2.x
except ImportError:
from io import StringIO #Python 3.x
MSG_TYPE_TO_CPP = {'byte': 'int8_t',
'char': 'uint8_t',
'bool': 'uint8_t',
'uint8': 'uint8_t',
'int8': 'int8_t',
'uint16': 'uint16_t',
'int16': 'int16_t',
'uint32': 'uint32_t',
'int32': 'int32_t',
'uint64': 'uint64_t',
'int64': 'int64_t',
'float32': 'float',
'float64': 'double',
'string': 'std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > ',
'time': 'ros::Time',
'duration': 'ros::Duration'}
#used
def msg_type_to_cpp(type):
"""
Converts a message type (e.g. uint32, std_msgs/String, etc.) into the C++ declaration
for that type (e.g. uint32_t, std_msgs::String_<ContainerAllocator>)
@param type: The message type
@type type: str
@return: The C++ declaration
@rtype: str
"""
(base_type, is_array, array_len) = genmsg.msgs.parse_type(type)
cpp_type = None
if (genmsg.msgs.is_builtin(base_type)):
cpp_type = MSG_TYPE_TO_CPP[base_type]
elif (len(base_type.split('/')) == 1):
if (genmsg.msgs.is_header_type(base_type)):
cpp_type = ' ::std_msgs::Header_<ContainerAllocator> '
else:
cpp_type = '%s_<ContainerAllocator> '%(base_type)
else:
pkg = base_type.split('/')[0]
msg = base_type.split('/')[1]
cpp_type = ' ::%s::%s_<ContainerAllocator> '%(pkg, msg)
if (is_array):
if (array_len is None):
return 'std::vector<%s, typename ContainerAllocator::template rebind<%s>::other > '%(cpp_type, cpp_type)
else:
return 'boost::array<%s, %s> '%(cpp_type, array_len)
else:
return cpp_type
def _escape_string(s):
s = s.replace('\\', '\\\\')
s = s.replace('"', '\\"')
return s
def escape_message_definition(definition):
lines = definition.splitlines()
if not lines:
lines.append('')
s = StringIO()
for line in lines:
line = _escape_string(line)
s.write('%s\\n\\\n'%(line))
val = s.getvalue()
s.close()
return val
#used2
def cpp_message_declarations(name_prefix, msg):
"""
Returns the different possible C++ declarations for a message given the message itself.
@param name_prefix: The C++ prefix to be prepended to the name, e.g. "std_msgs::"
@type name_prefix: str
@param msg: The message type
@type msg: str
@return: A tuple of 3 different names. cpp_message_decelarations("std_msgs::", "String") returns the tuple
("std_msgs::String_", "std_msgs::String_<ContainerAllocator>", "std_msgs::String")
@rtype: str
"""
pkg, basetype = genmsg.names.package_resource_name(msg)
cpp_name = ' ::%s%s'%(name_prefix, msg)
if (pkg):
cpp_name = ' ::%s::%s'%(pkg, basetype)
return ('%s_'%(cpp_name), '%s_<ContainerAllocator> '%(cpp_name), '%s'%(cpp_name))
#todo
def is_fixed_length(spec, msg_context, includepath):
"""
Returns whether or not the message is fixed-length
@param spec: The message spec
@type spec: genmsg.msgs.MsgSpec
@param package: The package of the
@type package: str
"""
types = []
for field in spec.parsed_fields():
if (field.is_array and field.array_len is None):
return False
if (field.base_type == 'string'):
return False
if (not field.is_builtin):
types.append(field.base_type)
types = set(types)
for t in types:
t = genmsg.msgs.resolve_type(t, spec.package)
assert isinstance(includepath, dict)
new_spec = genmsg.msg_loader.load_msg_by_type(msg_context, t, includepath)
if (not is_fixed_length(new_spec, msg_context, includepath)):
return False
return True
#used2
def default_value(type):
"""
Returns the value to initialize a message member with. 0 for integer types, 0.0 for floating point, false for bool,
empty string for everything else
@param type: The type
@type type: str
"""
if type in ['byte', 'int8', 'int16', 'int32', 'int64',
'char', 'uint8', 'uint16', 'uint32', 'uint64']:
return '0'
elif type in ['float32', 'float64']:
return '0.0'
elif type == 'bool':
return 'false'
return ""
#used2
def takes_allocator(type):
"""
Returns whether or not a type can take an allocator in its constructor. False for all builtin types except string.
True for all others.
@param type: The type
@type: str
"""
return not type in ['byte', 'int8', 'int16', 'int32', 'int64',
'char', 'uint8', 'uint16', 'uint32', 'uint64',
'float32', 'float64', 'bool', 'time', 'duration']
def escape_string(str):
str = str.replace('\\', '\\\\')
str = str.replace('"', '\\"')
return str
#used
def generate_fixed_length_assigns(spec, container_gets_allocator, cpp_name_prefix):
"""
Initialize any fixed-length arrays
@param s: The stream to write to
@type s: stream
@param spec: The message spec
@type spec: genmsg.msgs.MsgSpec
@param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
@type container_gets_allocator: bool
@param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
@type cpp_name_prefix: str
"""
# Assign all fixed-length arrays their default values
for field in spec.parsed_fields():
if (not field.is_array or field.array_len is None):
continue
val = default_value(field.base_type)
if (container_gets_allocator and takes_allocator(field.base_type)):
# String is a special case, as it is the only builtin type that takes an allocator
if (field.base_type == "string"):
string_cpp = msg_type_to_cpp("string")
yield ' %s.assign(%s(_alloc));\n'%(field.name, string_cpp)
else:
(cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, field.base_type)
yield ' %s.assign(%s(_alloc));\n'%(field.name, cpp_msg_with_alloc)
elif (len(val) > 0):
yield ' %s.assign(%s);\n'%(field.name, val)
#used
def generate_initializer_list(spec, container_gets_allocator):
"""
Writes the initializer list for a constructor
@param s: The stream to write to
@type s: stream
@param spec: The message spec
@type spec: genmsg.msgs.MsgSpec
@param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
@type container_gets_allocator: bool
"""
op = ':'
for field in spec.parsed_fields():
val = default_value(field.base_type)
use_alloc = takes_allocator(field.base_type)
if (field.is_array):
if (field.array_len is None and container_gets_allocator):
yield ' %s %s(_alloc)'%(op, field.name)
else:
yield ' %s %s()'%(op, field.name)
else:
if (container_gets_allocator and use_alloc):
yield ' %s %s(_alloc)'%(op, field.name)
else:
yield ' %s %s(%s)'%(op, field.name, val)
op = ','

3
mk/VRBRAIN/Tools/genmsg/.gitignore vendored Normal file
View File

@ -0,0 +1,3 @@
*.pyc
._*
*~

View File

@ -0,0 +1,13 @@
syntax: glob
*.orig
*.swp
*.pyc
*.DS_Store
*~
*.log
MANIFEST
.coverage
nosetests.xml
syntax: regexp
(target|build|dist)/.*

View File

@ -0,0 +1,83 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package genmsg
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.5.6 (2014-10-13)
------------------
* fix interpreter globals collision with multiple message templates or modules (`#53 <https://github.com/ros/genmsg/issues/53>`_)
0.5.5 (2014-08-18)
------------------
* fix CMake syntax (`#52 <https://github.com/ros/genmsg/issues/52>`_) (regression of 0.5.4)
0.5.4 (2014-08-18)
------------------
* allow DIRECTORY argument to be an absolute path (`#51 <https://github.com/ros/genmsg/issues/51>`_)
0.5.3 (2014-07-10)
------------------
* escape messages to avoid CMake warning (`#49 <https://github.com/ros/genmsg/issues/49>`_)
0.5.2 (2014-05-07)
------------------
* refactor to generate pkg-msg-paths.cmake via configure_file() instead of empy (`#43 <https://github.com/ros/genmsg/issues/43>`_)
* fix python 3 compatibility (`#45 <https://github.com/ros/genmsg/issues/45>`_)
* remove debug message introduced in 0.5.1 (`#42 <https://github.com/ros/genmsg/issues/42>`_)
0.5.1 (2014-03-04)
------------------
* add check for changed message dependencies (`#41 <https://github.com/ros/genmsg/issues/41>`_)
0.5.0 (2014-02-25)
------------------
* remove usage of debug_message() (`#40 <https://github.com/ros/genmsg/issues/40>`_)
0.4.24 (2014-01-07)
-------------------
* python 3 compatibility (`#36 <https://github.com/ros/genmsg/issues/36>`_, `#37 <https://github.com/ros/genmsg/issues/37>`_)
* add support for ROS_LANG_DISABLE env variable (`ros/ros#39 <https://github.com/ros/ros/issues/39>`_)
* fix installation of __init__.py from devel space (`#38 <https://github.com/ros/genmsg/issues/38>`_)
0.4.23 (2013-09-17)
-------------------
* fix installation of __init__.py file for packages where name differs from project name (`#34 <https://github.com/ros/genmsg/issues/34>`_)
* rename variable 'config' to not collide with global variable (`#33 <https://github.com/ros/genmsg/issues/33>`_)
* fix service files variable to only contain package relative paths (`#32 <https://github.com/ros/genmsg/issues/32>`_)
0.4.22 (2013-08-21)
-------------------
* make genmsg relocatable (`ros/catkin#490 <https://github.com/ros/catkin/issues/490>`_)
* add warning in case generate_messages() is invoked without any messages and services (`#31 <https://github.com/ros/genmsg/issues/31>`_)
* check if files have been generated before trying to install them (`#31 <https://github.com/ros/genmsg/issues/31>`_)
0.4.21 (2013-07-03)
-------------------
* check for CATKIN_ENABLE_TESTING to enable configure without tests
0.4.20 (2013-06-18)
-------------------
* generate pkg config extra files containing variables which list all message and service files (`#28 <https://github.com/ros/genmsg/issues/28>`_)
0.4.19 (2013-06-06)
-------------------
* improve error message for missing message dependencies (`#1 <https://github.com/ros/genmsg/issues/1>`_)
* fix generating duplicate include dirs for multiple add_message_files() invocations which broke generated lisp messages (`#27 <https://github.com/ros/genmsg/issues/27>`_)
0.4.18 (2013-03-08)
-------------------
* fix handling spaces in folder names (`ros/catkin#375 <https://github.com/ros/catkin/issues/375>`_)
* add targets with _generate_messages_LANG suffix (`#20 <https://github.com/ros/genmsg/issues/20>`_)
* pass all message generation target to EXPORTED_TARGETS (`#26 <https://github.com/ros/genmsg/issues/26>`_)
* improve error messages (`#22 <https://github.com/ros/genmsg/issues/22>`_)
0.4.17 (2013-01-19)
-------------------
* fix bug using ARGV in list(FIND) directly (`#18 <https://github.com/ros/genmsg/issues/18>`_)
0.4.16 (2013-01-13)
-------------------
* hide transitive message dependencies and pull them in automatically (`#15 <https://github.com/ros/genmsg/issues/15>`_)
0.4.15 (2012-12-21)
-------------------
* first public release for Groovy

View File

@ -0,0 +1,24 @@
cmake_minimum_required(VERSION 2.8.3)
project(genmsg)
find_package(catkin REQUIRED)
catkin_package(CFG_EXTRAS genmsg-extras.cmake)
install(
FILES
cmake/pkg-genmsg.cmake.em
cmake/pkg-genmsg.context.in
cmake/pkg-msg-extras.cmake.in
cmake/pkg-msg-paths.cmake.develspace.in
cmake/pkg-msg-paths.cmake.installspace.in
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake)
catkin_python_setup()
install(
PROGRAMS scripts/genmsg_check_deps.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
if(CATKIN_ENABLE_TESTING)
catkin_add_nosetests(test)
endif()

View File

@ -0,0 +1,315 @@
# generated from genmsg/cmake/genmsg-extras.cmake.in
if(_GENMSG_EXTRAS_INCLUDED_)
return()
endif()
set(_GENMSG_EXTRAS_INCLUDED_ TRUE)
# set destination for langs
set(GENMSG_LANGS_DESTINATION "etc/ros/genmsg")
@[if DEVELSPACE]@
# bin dir variables in develspace
set(GENMSG_CHECK_DEPS_SCRIPT "@(CMAKE_CURRENT_SOURCE_DIR)/scripts/genmsg_check_deps.py")
@[else]@
# bin dir variables in installspace
set(GENMSG_CHECK_DEPS_SCRIPT "${genmsg_DIR}/../../../@(CATKIN_PACKAGE_BIN_DESTINATION)/genmsg_check_deps.py")
@[end if]@
include(CMakeParseArguments)
# find message generators in all workspaces
set(message_generators "")
foreach(workspace ${CATKIN_WORKSPACES})
file(GLOB workspace_message_generators
RELATIVE ${workspace}/${GENMSG_LANGS_DESTINATION}
${workspace}/${GENMSG_LANGS_DESTINATION}/gen*)
list(APPEND message_generators ${workspace_message_generators})
endforeach()
if(message_generators)
list(SORT message_generators)
endif()
foreach(message_generator ${message_generators})
find_package(${message_generator} REQUIRED)
list(FIND CATKIN_MESSAGE_GENERATORS ${message_generator} _index)
if(_index EQUAL -1)
list(APPEND CATKIN_MESSAGE_GENERATORS ${message_generator})
endif()
endforeach()
if(CATKIN_MESSAGE_GENERATORS)
list(SORT CATKIN_MESSAGE_GENERATORS)
endif()
# disable specific message generators
string(REPLACE ":" ";" _disabled_message_generators "$ENV{ROS_LANG_DISABLE}")
# remove unknown generators from disabled list
foreach(message_generator ${_disabled_message_generators})
list(FIND CATKIN_MESSAGE_GENERATORS ${message_generator} _index)
if(_index EQUAL -1)
list(REMOVE_ITEM _disabled_message_generators ${message_generator})
message(WARNING "Unknown message generator specified in ROS_LANG_DISABLE: ${message_generator}")
endif()
endforeach()
if(_disabled_message_generators)
message(STATUS "Disabling the following message generators: ${_disabled_message_generators}")
list(REMOVE_ITEM CATKIN_MESSAGE_GENERATORS ${_disabled_message_generators})
endif()
message(STATUS "Using these message generators: ${CATKIN_MESSAGE_GENERATORS}")
macro(_prepend_path ARG_PATH ARG_FILES ARG_OUTPUT_VAR)
cmake_parse_arguments(ARG "UNIQUE" "" "" ${ARGN})
if(ARG_UNPARSED_ARGUMENTS)
message(FATAL_ERROR "_prepend_path() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}")
endif()
# todo, check for proper path, slasheds, etc
set(${ARG_OUTPUT_VAR} "")
foreach(_file ${ARG_FILES})
set(_value ${ARG_PATH}/${_file})
list(FIND ${ARG_OUTPUT_VAR} ${_value} _index)
if(NOT ARG_UNIQUE OR _index EQUAL -1)
list(APPEND ${ARG_OUTPUT_VAR} ${_value})
endif()
endforeach()
endmacro()
macro(add_message_files)
cmake_parse_arguments(ARG "NOINSTALL" "DIRECTORY;BASE_DIR" "FILES" ${ARGN})
if(ARG_UNPARSED_ARGUMENTS)
message(FATAL_ERROR "add_message_files() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}")
endif()
if(NOT ARG_DIRECTORY)
set(ARG_DIRECTORY "msg")
endif()
set(MESSAGE_DIR "${ARG_DIRECTORY}")
if(NOT IS_ABSOLUTE "${MESSAGE_DIR}")
set(MESSAGE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/${MESSAGE_DIR}")
endif()
# override message directory (used by add_action_files())
if(ARG_BASE_DIR)
set(MESSAGE_DIR ${ARG_BASE_DIR})
endif()
if(NOT IS_DIRECTORY ${MESSAGE_DIR})
message(FATAL_ERROR "add_message_files() directory not found: ${MESSAGE_DIR}")
endif()
if(${PROJECT_NAME}_GENERATE_MESSAGES)
message(FATAL_ERROR "generate_messages() must be called after add_message_files()")
endif()
# if FILES are not passed search message files in the given directory
# note: ARGV is not variable, so it can not be passed to list(FIND) directly
set(_argv ${ARGV})
list(FIND _argv "FILES" _index)
if(_index EQUAL -1)
file(GLOB ARG_FILES RELATIVE "${MESSAGE_DIR}" "${MESSAGE_DIR}/*.msg")
list(SORT ARG_FILES)
endif()
_prepend_path(${MESSAGE_DIR} "${ARG_FILES}" FILES_W_PATH)
list(APPEND ${PROJECT_NAME}_MESSAGE_FILES ${FILES_W_PATH})
foreach(file ${FILES_W_PATH})
assert_file_exists(${file} "message file not found")
endforeach()
# remember path to messages to resolve them as dependencies
list(FIND ${PROJECT_NAME}_MSG_INCLUDE_DIRS_DEVELSPACE ${MESSAGE_DIR} _index)
if(_index EQUAL -1)
list(APPEND ${PROJECT_NAME}_MSG_INCLUDE_DIRS_DEVELSPACE ${MESSAGE_DIR})
endif()
if(NOT ARG_NOINSTALL)
# ensure that destination variables are initialized
catkin_destinations()
list(APPEND ${PROJECT_NAME}_MSG_INCLUDE_DIRS_INSTALLSPACE ${ARG_DIRECTORY})
install(FILES ${FILES_W_PATH}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${ARG_DIRECTORY})
_prepend_path("${ARG_DIRECTORY}" "${ARG_FILES}" FILES_W_PATH)
list(APPEND ${PROJECT_NAME}_INSTALLED_MESSAGE_FILES ${FILES_W_PATH})
endif()
endmacro()
macro(add_service_files)
cmake_parse_arguments(ARG "NOINSTALL" "DIRECTORY" "FILES" ${ARGN})
if(ARG_UNPARSED_ARGUMENTS)
message(FATAL_ERROR "add_service_files() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}")
endif()
if(NOT ARG_DIRECTORY)
set(ARG_DIRECTORY "srv")
endif()
set(SERVICE_DIR "${ARG_DIRECTORY}")
if(NOT IS_ABSOLUTE "${SERVICE_DIR}")
set(SERVICE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/${SERVICE_DIR}")
endif()
if(NOT IS_DIRECTORY ${SERVICE_DIR})
message(FATAL_ERROR "add_service_files() directory not found: ${SERVICE_DIR}")
endif()
if(${PROJECT_NAME}_GENERATE_MESSAGES)
message(FATAL_ERROR "generate_messages() must be called after add_service_files()")
endif()
# if FILES are not passed search service files in the given directory
# note: ARGV is not variable, so it can not be passed to list(FIND) directly
set(_argv ${ARGV})
list(FIND _argv "FILES" _index)
if(_index EQUAL -1)
file(GLOB ARG_FILES RELATIVE "${SERVICE_DIR}" "${SERVICE_DIR}/*.srv")
list(SORT ARG_FILES)
endif()
_prepend_path(${SERVICE_DIR} "${ARG_FILES}" FILES_W_PATH)
list(APPEND ${PROJECT_NAME}_SERVICE_FILES ${FILES_W_PATH})
foreach(file ${FILES_W_PATH})
assert_file_exists(${file} "service file not found")
endforeach()
if(NOT ARG_NOINSTALL)
# ensure that destination variables are initialized
catkin_destinations()
install(FILES ${FILES_W_PATH}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${ARG_DIRECTORY})
_prepend_path("${ARG_DIRECTORY}" "${ARG_FILES}" FILES_W_PATH)
list(APPEND ${PROJECT_NAME}_INSTALLED_SERVICE_FILES ${FILES_W_PATH})
endif()
endmacro()
macro(generate_messages)
cmake_parse_arguments(ARG "" "" "DEPENDENCIES;LANGS" ${ARGN})
if(${PROJECT_NAME}_GENERATE_MESSAGES)
message(FATAL_ERROR "generate_messages() must only be called once per project'")
endif()
if(ARG_UNPARSED_ARGUMENTS)
message(FATAL_ERROR "generate_messages() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}")
endif()
if(${PROJECT_NAME}_CATKIN_PACKAGE)
message(FATAL_ERROR "generate_messages() must be called before catkin_package() in project '${PROJECT_NAME}'")
endif()
set(ARG_MESSAGES ${${PROJECT_NAME}_MESSAGE_FILES})
set(ARG_SERVICES ${${PROJECT_NAME}_SERVICE_FILES})
set(ARG_DEPENDENCIES ${ARG_DEPENDENCIES})
if(ARG_LANGS)
set(GEN_LANGS ${ARG_LANGS})
else()
set(GEN_LANGS ${CATKIN_MESSAGE_GENERATORS})
endif()
@[if DEVELSPACE]@
# cmake dir in develspace
set(genmsg_CMAKE_DIR "@(CMAKE_CURRENT_SOURCE_DIR)/cmake")
@[else]@
# cmake dir in installspace
set(genmsg_CMAKE_DIR "@(PKG_CMAKE_DIR)")
@[end if]@
# ensure that destination variables are initialized
catkin_destinations()
# generate devel space config of message include dirs for project
set(PKG_MSG_INCLUDE_DIRS "${${PROJECT_NAME}_MSG_INCLUDE_DIRS_DEVELSPACE}")
configure_file(
${genmsg_CMAKE_DIR}/pkg-msg-paths.cmake.develspace.in
${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}-msg-paths.cmake
@@ONLY)
# generate and install config of message include dirs for project
set(PKG_MSG_INCLUDE_DIRS "${${PROJECT_NAME}_MSG_INCLUDE_DIRS_INSTALLSPACE}")
configure_file(
${genmsg_CMAKE_DIR}/pkg-msg-paths.cmake.installspace.in
${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/installspace/${PROJECT_NAME}-msg-paths.cmake
@@ONLY)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/installspace/${PROJECT_NAME}-msg-paths.cmake
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake)
# generate devel space pkg config extra defining variables with all processed message and service files
set(PKG_MSG_FILES "${${PROJECT_NAME}_MESSAGE_FILES}")
set(PKG_SRV_FILES "${${PROJECT_NAME}_SERVICE_FILES}")
configure_file(
${genmsg_CMAKE_DIR}/pkg-msg-extras.cmake.in
${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/${PROJECT_NAME}-msg-extras.cmake.develspace.in
@@ONLY)
# generate install space pkg config extra defining variables with all processed and installed message and service files
set(PKG_MSG_FILES "${${PROJECT_NAME}_INSTALLED_MESSAGE_FILES}")
set(PKG_SRV_FILES "${${PROJECT_NAME}_INSTALLED_SERVICE_FILES}")
configure_file(
${genmsg_CMAKE_DIR}/pkg-msg-extras.cmake.in
${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/${PROJECT_NAME}-msg-extras.cmake.installspace.in
@@ONLY)
# register pkg config files as cmake extra file for the project
list(APPEND ${PROJECT_NAME}_CFG_EXTRAS ${CMAKE_CURRENT_BINARY_DIR}/catkin_generated/${PROJECT_NAME}-msg-extras.cmake)
# find configuration containing include dirs for projects in all devel- and installspaces
set(workspaces ${CATKIN_WORKSPACES})
list(FIND workspaces ${CATKIN_DEVEL_PREFIX} _index)
if(_index EQUAL -1)
list(INSERT workspaces 0 ${CATKIN_DEVEL_PREFIX})
endif()
set(pending_deps ${PROJECT_NAME} ${ARG_DEPENDENCIES})
set(handled_deps "")
while(pending_deps)
list(GET pending_deps 0 dep)
list(REMOVE_AT pending_deps 0)
list(APPEND handled_deps ${dep})
if(NOT ${dep}_FOUND AND NOT ${dep}_SOURCE_DIR)
message(FATAL_ERROR "Messages depends on unknown pkg: ${dep} (Missing find_package(${dep}?))")
endif()
unset(_dep_msg_paths_file CACHE)
set(filename "share/${dep}/cmake/${dep}-msg-paths.cmake")
find_file(_dep_msg_paths_file ${filename} PATHS ${workspaces}
NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)
if("${_dep_msg_paths_file}" STREQUAL "_dep_msg_paths_file-NOTFOUND")
message(FATAL_ERROR "Could not find '${filename}' (searched in '${workspaces}').")
endif()
include(${_dep_msg_paths_file})
unset(_dep_msg_paths_file CACHE)
# explicitly set message include dirs for current project since information from pkg-msg-paths.cmake is not yet available
if(${dep} STREQUAL ${PROJECT_NAME})
set(${dep}_MSG_INCLUDE_DIRS ${${PROJECT_NAME}_MSG_INCLUDE_DIRS_DEVELSPACE})
endif()
foreach(path ${${dep}_MSG_INCLUDE_DIRS})
list(APPEND MSG_INCLUDE_DIRS "${dep}")
list(APPEND MSG_INCLUDE_DIRS "${path}")
endforeach()
# add transitive msg dependencies
if(NOT ${dep} STREQUAL ${PROJECT_NAME})
foreach(recdep ${${dep}_MSG_DEPENDENCIES})
set(all_deps ${handled_deps} ${pending_deps})
list(FIND all_deps ${recdep} _index)
if(_index EQUAL -1)
list(APPEND pending_deps ${recdep})
endif()
endforeach()
endif()
endwhile()
# mark that generate_messages() was called in order to detect wrong order of calling with catkin_python_setup()
set(${PROJECT_NAME}_GENERATE_MESSAGES TRUE)
# check if catkin_python_setup() installs an __init__.py file for a package with the current project name
# in order to skip the installation of a generated __init__.py file
set(package_has_static_sources ${${PROJECT_NAME}_CATKIN_PYTHON_SETUP_HAS_PACKAGE_INIT})
em_expand(${genmsg_CMAKE_DIR}/pkg-genmsg.context.in
${CMAKE_CURRENT_BINARY_DIR}/cmake/${PROJECT_NAME}-genmsg-context.py
${genmsg_CMAKE_DIR}/pkg-genmsg.cmake.em
${CMAKE_CURRENT_BINARY_DIR}/cmake/${PROJECT_NAME}-genmsg.cmake)
include(${CMAKE_CURRENT_BINARY_DIR}/cmake/${PROJECT_NAME}-genmsg.cmake)
endmacro()

View File

@ -0,0 +1,164 @@
# generated from genmsg/cmake/pkg-genmsg.cmake.em
@{
import os
import sys
import genmsg
import genmsg.base
genmsg.base.log_verbose('GENMSG_VERBOSE' in os.environ)
import genmsg.deps
import genmsg.gentools
# split incoming variables
messages = messages_str.split(';') if messages_str != '' else []
services = services_str.split(';') if services_str != '' else []
dependencies = dependencies_str.split(';') if dependencies_str != '' else []
dep_search_paths = dep_include_paths_str.split(';') if dep_include_paths_str != '' else []
dep_search_paths_dict = {}
dep_search_paths_tuple_list = []
is_even = True
for val in dep_search_paths:
if is_even:
dep_search_paths_dict.setdefault(val, [])
val_prev = val
is_even = False
else:
dep_search_paths_dict[val_prev].append(val)
dep_search_paths_tuple_list.append((val_prev, val))
is_even = True
dep_search_paths = dep_search_paths_dict
if not messages and not services:
print('message(WARNING "Invoking generate_messages() without having added any message or service file before.\nYou should either add add_message_files() and/or add_service_files() calls or remove the invocation of generate_messages().")')
msg_deps = {}
msg_dep_types = {}
for m in messages:
try:
_deps = genmsg.deps.find_msg_dependencies_with_type(pkg_name, m, dep_search_paths)
msg_deps[m] = [d[1] for d in _deps]
msg_dep_types[m] = [d[0] for d in _deps]
except genmsg.MsgNotFound as e:
print('message(FATAL_ERROR "Could not find messages which \'%s\' depends on. Did you forget to specify generate_messages(DEPENDENCIES ...)?\n%s")' % (m, str(e).replace('"', '\\"')))
srv_deps = {}
srv_dep_types = {}
for s in services:
try:
_deps = genmsg.deps.find_srv_dependencies_with_type(pkg_name, s, dep_search_paths)
srv_deps[s] = [d[1] for d in _deps]
srv_dep_types[s] = [d[0] for d in _deps]
except genmsg.MsgNotFound as e:
print('message(FATAL_ERROR "Could not find messages which \'%s\' depends on. Did you forget to specify generate_messages(DEPENDENCIES ...)?\n%s")' % (s, str(e).replace('"', '\\"')))
}@
message(STATUS "@(pkg_name): @(len(messages)) messages, @(len(services)) services")
set(MSG_I_FLAGS "@(';'.join(["-I%s:%s" % (dep, dir) for dep, dir in dep_search_paths_tuple_list]))")
# Find all generators
@[if langs]@
@[for l in langs.split(';')]@
find_package(@l REQUIRED)
@[end for]@
@[end if]@
add_custom_target(@(pkg_name)_generate_messages ALL)
# verify that message/service dependencies have not changed since configure
@{all_deps = dict(list(msg_deps.items()) + list(srv_deps.items()))}
@{all_dep_types = dict(list(msg_dep_types.items()) + list(srv_dep_types.items()))}
@[for f in all_deps.keys()]@
@{dep_types = ':'.join(all_dep_types[f]).replace('\\','/')}
get_filename_component(_filename "@(f)" NAME_WE)
add_custom_target(_@(pkg_name)_generate_messages_check_deps_${_filename}
COMMAND ${CATKIN_ENV} ${PYTHON_EXECUTABLE} ${GENMSG_CHECK_DEPS_SCRIPT} "@(pkg_name)" "@(f)" "@(dep_types)"
)
@[end for]@# messages and services
#
# langs = @langs
#
@[if langs]@
@[for l in langs.split(';')]@
### Section generating for lang: @l
### Generating Messages
@[for m in msg_deps.keys()]@
_generate_msg_@(l[3:])(@pkg_name
"@m"
"${MSG_I_FLAGS}"
"@(';'.join(msg_deps[m]).replace("\\","/"))"
${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name
)
@[end for]@# messages
### Generating Services
@[for s in srv_deps.keys()]@
_generate_srv_@(l[3:])(@pkg_name
"@s"
"${MSG_I_FLAGS}"
"@(';'.join(srv_deps[s]).replace("\\","/"))"
${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name
)
@[end for]@# services
### Generating Module File
_generate_module_@(l[3:])(@pkg_name
${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name
"${ALL_GEN_OUTPUT_FILES_@(l[3:])}"
)
add_custom_target(@(pkg_name)_generate_messages_@(l[3:])
DEPENDS ${ALL_GEN_OUTPUT_FILES_@(l[3:])}
)
add_dependencies(@(pkg_name)_generate_messages @(pkg_name)_generate_messages_@(l[3:]))
# add dependencies to all check dependencies targets
@[for f in all_deps.keys()]@
get_filename_component(_filename "@(f)" NAME_WE)
add_dependencies(@(pkg_name)_generate_messages_@(l[3:]) _@(pkg_name)_generate_messages_check_deps_${_filename})
@[end for]@# messages and services
# target for backward compatibility
add_custom_target(@(pkg_name)_@(l))
add_dependencies(@(pkg_name)_@(l) @(pkg_name)_generate_messages_@(l[3:]))
# register target for catkin_package(EXPORTED_TARGETS)
list(APPEND ${PROJECT_NAME}_EXPORTED_TARGETS @(pkg_name)_generate_messages_@(l[3:]))
@[end for]@# langs
@[end if]@
@[if langs]@
@[for l in langs.split(';')]@
if(@(l)_INSTALL_DIR AND EXISTS ${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name)
@[if l == 'genpy']@
install(CODE "execute_process(COMMAND \"@(PYTHON_EXECUTABLE)\" -m compileall \"${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name\")")
@[end if]@
# install generated code
install(
DIRECTORY ${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name
DESTINATION ${@(l)_INSTALL_DIR}
@[if l == 'genpy' and package_has_static_sources]@
# skip all init files
PATTERN "__init__.py" EXCLUDE
PATTERN "__init__.pyc" EXCLUDE
)
# install init files which are not in the root folder of the generated code
install(
DIRECTORY ${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@pkg_name
DESTINATION ${@(l)_INSTALL_DIR}
FILES_MATCHING
REGEX "${CATKIN_DEVEL_PREFIX}/${@(l)_INSTALL_DIR}/@(pkg_name)/.+/__init__.pyc?$"
@[end if]@
)
endif()
@[for d in dependencies]@
add_dependencies(@(pkg_name)_generate_messages_@(l[3:]) @(d)_generate_messages_@(l[3:]))
@[end for]@# dependencies
@[end for]@# langs
@[end if]@

View File

@ -0,0 +1,11 @@
# generated from genmsg/cmake/pkg-genmsg.context.in
messages_str = "@ARG_MESSAGES@"
services_str = "@ARG_SERVICES@"
pkg_name = "@PROJECT_NAME@"
dependencies_str = "@ARG_DEPENDENCIES@"
langs = "@GEN_LANGS@"
dep_include_paths_str = "@MSG_INCLUDE_DIRS@"
PYTHON_EXECUTABLE = "@PYTHON_EXECUTABLE@"
package_has_static_sources = '@package_has_static_sources@' == 'TRUE'
genmsg_check_deps_script = "@GENMSG_CHECK_DEPS_SCRIPT@"

View File

@ -0,0 +1,2 @@
set(@PROJECT_NAME@_MESSAGE_FILES "@PKG_MSG_FILES@")
set(@PROJECT_NAME@_SERVICE_FILES "@PKG_SRV_FILES@")

View File

@ -0,0 +1,4 @@
# generated from genmsg/cmake/pkg-msg-paths.cmake.develspace.in
set(@PROJECT_NAME@_MSG_INCLUDE_DIRS "@PKG_MSG_INCLUDE_DIRS@")
set(@PROJECT_NAME@_MSG_DEPENDENCIES @ARG_DEPENDENCIES@)

View File

@ -0,0 +1,4 @@
# generated from genmsg/cmake/pkg-msg-paths.cmake.installspace.in
_prepend_path("${@PROJECT_NAME@_DIR}/.." "@PKG_MSG_INCLUDE_DIRS@" @PROJECT_NAME@_MSG_INCLUDE_DIRS UNIQUE)
set(@PROJECT_NAME@_MSG_DEPENDENCIES @ARG_DEPENDENCIES@)

View File

@ -0,0 +1,135 @@
# Makefile for Sphinx documentation
#
# You can set these variables from the command line.
SPHINXOPTS =
SPHINXBUILD = sphinx-build
PAPER =
BUILDDIR = _build
# Internal variables.
PAPEROPT_a4 = -D latex_paper_size=a4
PAPEROPT_letter = -D latex_paper_size=letter
ALLSPHINXOPTS = -d $(BUILDDIR)/doctrees $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .
.PHONY: help clean html dirhtml singlehtml pickle json htmlhelp qthelp devhelp epub latex latexpdf text man changes linkcheck doctest
help:
@echo "Please use \`make <target>' where <target> is one of"
@echo " html to make standalone HTML files"
@echo " dirhtml to make HTML files named index.html in directories"
@echo " singlehtml to make a single large HTML file"
@echo " pickle to make pickle files"
@echo " json to make JSON files"
@echo " htmlhelp to make HTML files and a HTML help project"
@echo " qthelp to make HTML files and a qthelp project"
@echo " devhelp to make HTML files and a Devhelp project"
@echo " epub to make an epub"
@echo " latex to make LaTeX files, you can set PAPER=a4 or PAPER=letter"
@echo " latexpdf to make LaTeX files and run them through pdflatex"
@echo " text to make text files"
@echo " man to make manual pages"
@echo " changes to make an overview of all changed/added/deprecated items"
@echo " linkcheck to check all external links for integrity"
@echo " doctest to run all doctests embedded in the documentation (if enabled)"
clean:
-rm -rf $(BUILDDIR)/*
html:
$(SPHINXBUILD) -b html $(ALLSPHINXOPTS) $(BUILDDIR)/html
@echo
@echo "Build finished. The HTML pages are in $(BUILDDIR)/html."
dirhtml:
$(SPHINXBUILD) -b dirhtml $(ALLSPHINXOPTS) $(BUILDDIR)/dirhtml
@echo
@echo "Build finished. The HTML pages are in $(BUILDDIR)/dirhtml."
singlehtml:
$(SPHINXBUILD) -b singlehtml $(ALLSPHINXOPTS) $(BUILDDIR)/singlehtml
@echo
@echo "Build finished. The HTML page is in $(BUILDDIR)/singlehtml."
pickle:
$(SPHINXBUILD) -b pickle $(ALLSPHINXOPTS) $(BUILDDIR)/pickle
@echo
@echo "Build finished; now you can process the pickle files."
json:
$(SPHINXBUILD) -b json $(ALLSPHINXOPTS) $(BUILDDIR)/json
@echo
@echo "Build finished; now you can process the JSON files."
htmlhelp:
$(SPHINXBUILD) -b htmlhelp $(ALLSPHINXOPTS) $(BUILDDIR)/htmlhelp
@echo
@echo "Build finished; now you can run HTML Help Workshop with the" \
".hhp project file in $(BUILDDIR)/htmlhelp."
qthelp:
$(SPHINXBUILD) -b qthelp $(ALLSPHINXOPTS) $(BUILDDIR)/qthelp
@echo
@echo "Build finished; now you can run "qcollectiongenerator" with the" \
".qhcp project file in $(BUILDDIR)/qthelp, like this:"
@echo "# qcollectiongenerator $(BUILDDIR)/qthelp/genmsg.qhcp"
@echo "To view the help file:"
@echo "# assistant -collectionFile $(BUILDDIR)/qthelp/genmsg.qhc"
devhelp:
$(SPHINXBUILD) -b devhelp $(ALLSPHINXOPTS) $(BUILDDIR)/devhelp
@echo
@echo "Build finished."
@echo "To view the help file:"
@echo "# mkdir -p $$HOME/.local/share/devhelp/genmsg"
@echo "# ln -s $(BUILDDIR)/devhelp $$HOME/.local/share/devhelp/genmsg"
@echo "# devhelp"
epub:
$(SPHINXBUILD) -b epub $(ALLSPHINXOPTS) $(BUILDDIR)/epub
@echo
@echo "Build finished. The epub file is in $(BUILDDIR)/epub."
latex:
$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex
@echo
@echo "Build finished; the LaTeX files are in $(BUILDDIR)/latex."
@echo "Run \`make' in that directory to run these through (pdf)latex" \
"(use \`make latexpdf' here to do that automatically)."
latexpdf:
$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex
@echo "Running LaTeX files through pdflatex..."
make -C $(BUILDDIR)/latex all-pdf
@echo "pdflatex finished; the PDF files are in $(BUILDDIR)/latex."
text:
$(SPHINXBUILD) -b text $(ALLSPHINXOPTS) $(BUILDDIR)/text
@echo
@echo "Build finished. The text files are in $(BUILDDIR)/text."
man:
$(SPHINXBUILD) -b man $(ALLSPHINXOPTS) $(BUILDDIR)/man
@echo
@echo "Build finished. The manual pages are in $(BUILDDIR)/man."
changes:
$(SPHINXBUILD) -b changes $(ALLSPHINXOPTS) $(BUILDDIR)/changes
@echo
@echo "The overview file is in $(BUILDDIR)/changes."
linkcheck:
$(SPHINXBUILD) -b linkcheck $(ALLSPHINXOPTS) $(BUILDDIR)/linkcheck
@echo
@echo "Link check complete; look for any errors in the above output " \
"or in $(BUILDDIR)/linkcheck/output.txt."
doctest:
$(SPHINXBUILD) -b doctest $(ALLSPHINXOPTS) $(BUILDDIR)/doctest
@echo "Testing of doctests in the sources finished, look at the " \
"results in $(BUILDDIR)/doctest/output.txt."
upload: html
scp -r _build/html/ wgs32.willowgarage.com:/var/www/www.ros.org/html/doc/api/genmsg/
scp -r _build/html/ wgs32.willowgarage.com:/var/www/www.ros.org/html/doc/fuerte/api/genmsg/

View File

@ -0,0 +1,263 @@
# -*- coding: utf-8 -*-
#
# genmsg documentation build configuration file, created by
# sphinx-quickstart on Wed Dec 14 07:48:35 2011.
#
# This file is execfile()d with the current directory set to its containing dir.
#
# Note that not all possible configuration values are present in this
# autogenerated file.
#
# All configuration values have a default; values that are commented out
# serve to show the default.
import sys, os
import catkin_sphinx
sys.path.insert(0, '../src')
from xml.etree.ElementTree import ElementTree
# If extensions (or modules to document with autodoc) are in another directory,
# add these directories to sys.path here. If the directory is relative to the
# documentation root, use os.path.abspath to make it absolute, like shown here.
#sys.path.insert(0, os.path.abspath('.'))
# -- General configuration -----------------------------------------------------
# If your documentation needs a minimal Sphinx version, state it here.
#needs_sphinx = '1.0'
html_logo = 'ros.png'
html_theme_path = [os.path.join(os.path.dirname(catkin_sphinx.__file__),
'theme')]
# Add any Sphinx extension module names here, as strings. They can be extensions
# coming with Sphinx (named 'sphinx.ext.*') or your custom ones.
extensions = ['sphinx.ext.autodoc', 'sphinx.ext.intersphinx', 'sphinx.ext.todo', 'sphinx.ext.viewcode', 'catkin_sphinx.cmake']
# Add any paths that contain templates here, relative to this directory.
templates_path = ['_templates']
# The suffix of source filenames.
source_suffix = '.rst'
# The encoding of source files.
#source_encoding = 'utf-8-sig'
# The master toctree document.
master_doc = 'index'
# General information about the project.
project = u'genmsg'
copyright = u'2011, Willow Garage'
# The version info for the project you're documenting, acts as replacement for
# |version| and |release|, also used in various other places throughout the
# built documents.
try:
root = ElementTree(None, os.path.join('..', 'package.xml'))
version = root.findtext('version')
except Exception as e:
raise RuntimeError('Could not extract version from package.xml:\n%s' % e)
# The full version, including alpha/beta/rc tags.
release = version
# The language for content autogenerated by Sphinx. Refer to documentation
# for a list of supported languages.
#language = None
# There are two options for replacing |today|: either, you set today to some
# non-false value, then it is used:
#today = ''
# Else, today_fmt is used as the format for a strftime call.
#today_fmt = '%B %d, %Y'
# List of patterns, relative to source directory, that match files and
# directories to ignore when looking for source files.
exclude_patterns = ['_build']
# The reST default role (used for this markup: `text`) to use for all documents.
#default_role = None
# If true, '()' will be appended to :func: etc. cross-reference text.
#add_function_parentheses = True
# If true, the current module name will be prepended to all description
# unit titles (such as .. function::).
#add_module_names = True
# If true, sectionauthor and moduleauthor directives will be shown in the
# output. They are ignored by default.
#show_authors = False
# The name of the Pygments (syntax highlighting) style to use.
pygments_style = 'sphinx'
# A list of ignored prefixes for module index sorting.
#modindex_common_prefix = []
# -- Options for HTML output ---------------------------------------------------
# The theme to use for HTML and HTML Help pages. See the documentation for
# a list of builtin themes.
html_theme = 'ros-theme'
# Theme options are theme-specific and customize the look and feel of a theme
# further. For a list of options available for each theme, see the
# documentation.
#html_theme_options = {}
# Add any paths that contain custom themes here, relative to this directory.
#html_theme_path = []
# The name for this set of Sphinx documents. If None, it defaults to
# "<project> v<release> documentation".
#html_title = None
# A shorter title for the navigation bar. Default is the same as html_title.
#html_short_title = None
# The name of an image file (relative to this directory) to place at the top
# of the sidebar.
#html_logo = None
# The name of an image file (within the static path) to use as favicon of the
# docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32
# pixels large.
#html_favicon = None
# Add any paths that contain custom static files (such as style sheets) here,
# relative to this directory. They are copied after the builtin static files,
# so a file named "default.css" will overwrite the builtin "default.css".
html_static_path = ['_static']
# If not '', a 'Last updated on:' timestamp is inserted at every page bottom,
# using the given strftime format.
#html_last_updated_fmt = '%b %d, %Y'
# If true, SmartyPants will be used to convert quotes and dashes to
# typographically correct entities.
#html_use_smartypants = True
# Custom sidebar templates, maps document names to template names.
#html_sidebars = {}
# Additional templates that should be rendered to pages, maps page names to
# template names.
#html_additional_pages = {}
# If false, no module index is generated.
#html_domain_indices = True
# If false, no index is generated.
#html_use_index = True
# If true, the index is split into individual pages for each letter.
#html_split_index = False
# If true, links to the reST sources are added to the pages.
#html_show_sourcelink = True
# If true, "Created using Sphinx" is shown in the HTML footer. Default is True.
#html_show_sphinx = True
# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True.
#html_show_copyright = True
# If true, an OpenSearch description file will be output, and all pages will
# contain a <link> tag referring to it. The value of this option must be the
# base URL from which the finished HTML is served.
#html_use_opensearch = ''
# This is the file name suffix for HTML files (e.g. ".xhtml").
#html_file_suffix = None
# Output file base name for HTML help builder.
htmlhelp_basename = 'genmsgdoc'
# -- Options for LaTeX output --------------------------------------------------
latex_elements = {
# The paper size ('letterpaper' or 'a4paper').
#'papersize': 'letterpaper',
# The font size ('10pt', '11pt' or '12pt').
#'pointsize': '10pt',
# Additional stuff for the LaTeX preamble.
#'preamble': '',
}
# Grouping the document tree into LaTeX files. List of tuples
# (source start file, target name, title, author, documentclass [howto/manual]).
latex_documents = [
('index', 'genmsg.tex', u'genmsg Documentation',
u'Willow Garage', 'manual'),
]
# The name of an image file (relative to this directory) to place at the top of
# the title page.
#latex_logo = None
# For "manual" documents, if this is true, then toplevel headings are parts,
# not chapters.
#latex_use_parts = False
# If true, show page references after internal links.
#latex_show_pagerefs = False
# If true, show URL addresses after external links.
#latex_show_urls = False
# Documents to append as an appendix to all manuals.
#latex_appendices = []
# If false, no module index is generated.
#latex_domain_indices = True
# -- Options for manual page output --------------------------------------------
# One entry per manual page. List of tuples
# (source start file, name, description, authors, manual section).
man_pages = [
('index', 'genmsg', u'genmsg Documentation',
[u'Willow Garage'], 1)
]
# If true, show URL addresses after external links.
#man_show_urls = False
# -- Options for Texinfo output ------------------------------------------------
# Grouping the document tree into Texinfo files. List of tuples
# (source start file, target name, title, author,
# dir menu entry, description, category)
texinfo_documents = [
('index', 'genmsg', u'genmsg Documentation',
u'Willow Garage', 'genmsg', 'One line description of project.',
'Miscellaneous'),
]
# Documents to append as an appendix to all manuals.
#texinfo_appendices = []
# If false, no module index is generated.
#texinfo_domain_indices = True
# How to display URL addresses: 'footnote', 'no', or 'inline'.
#texinfo_show_urls = 'footnote'
# Example configuration for intersphinx: refer to the Python standard library.
intersphinx_mapping = {
'genmsg': ('http://ros.org/doc/api/genmsg/html', None),
'vcstools': ('http://ros.org/doc/api/vcstools/html', None),
'rosinstall': ('http://ros.org/doc/api/rosinstall/html', None),
'rospkg': ('http://ros.org/doc/api/rosinstall/html', None),
'rosdep2': ('http://ros.org/doc/api/rosdep2/html', None),
}

View File

@ -0,0 +1,193 @@
Developer documenation
======================
Project ``genmsg`` exists in order to decouple code generation from
.msg format files from the parsing of these files and from
impementation details of the build system (project directory layout,
existence or nonexistence of utilities like ``rospack``, values of
environment variables such as ``ROS_PACKAGE_PATH``): i.e. none of
these are required to be set in any particular way.
Code generators expose a compiler-like interface that make all inputs,
outputs and search paths explicit. For instance, the invocation of
``gencpp`` for ros message ``nav_msgs/Odometry.msg`` looks like this::
/ssd/catkin/test/src/gencpp/scripts/gen_cpp.py
/ssd/catkin/test/src/common_msgs/nav_msgs/msg/Odometry.msg
-Inav_msgs:/ssd/catkin/test/src/common_msgs/nav_msgs/msg
-Igeometry_msgs:/ssd/catkin/test/src/common_msgs/geometry_msgs/msg
-Istd_msgs:/ssd/catkin/test/src/std_msgs/msg
-p nav_msgs
-o /ssd/catkin/test/build/gen/cpp/nav_msgs
-e /ssd/catkin/test/src/gencpp/scripts
where the code generator (the first argument), is a python script
``gen_cpp.py``. The commandline arguments have the following
meanings:
``/path/to/Some.msg``
The flagless argument is the path to the
input ``.msg`` file.
``-I NAMESPACE:/some/path``
find messages in NAMESPACE in directory /some/path
``-p THIS_NAMESPACE``
put generated message into namespace THIS_NAMESPACE
``-o /output/dir``
Generate code into directory :file:`/output/dir`
``-e /path/to/templates``
Find empy templates in this directory
Code generators may not use any information other than what is
provided on the commandline.
.. rubric:: Writing the generator
Code generators depend on ``genmsg`` to parse the .msg file itself.
They then use the parse tree to generate code in whatever language or
format they prefer.
A separate project must exists for each language you wish to generate for.
Such a project contains:
* A message_generator tag in the stack.xml file
* Executable scripts for generating the code based on .msg/.srv files
* Definitions of certain CMake macros to make the generator accessible by the build system.
Generator Scripts
~~~~~~~~~~~~~~~~~
The recommended way of implementing the generator is by using empy
template files. See: http://www.alcyone.com/software/empy A empy
template is a text file part of which can contain python code that is
evaluated during code generation. ``genmsg`` includes python methods
for parsing the command line arguments and performing the code
generation very easily if the template model is used.
The script for generating cpp files looks as::
import sys
import genmsg.template_tools
msg_template_map = { 'msg.h.template':'@NAME@.h' }
srv_template_map = { 'srv.h.template':'@NAME@.h' }
if __name__ == "__main__":
genmsg.template_tools.generate_from_command_line_options(sys.argv, msg_template_map, srv_template_map)
``msg_template_map`` and ``srv_template_map`` defines the template
files used for generating from .msg and .srv files respectively. The
format is ``<type>_template_map = {
'<template_filename>':'<output_file_name>' }``. The entry ``@NAME@``
will be replaced by the short name of the message such as ``String``
for ``String.msg`` etc. The call to
``generate_from_command_line_options`` will use the correct map
depending on the file gives as command line argument. When a service
is generated, two messages are also generated, namely the
``<SrvName>Request`` and ``<SrvName>Response``.
``genmsg`` will parse the respective .msg and .srv file and expose the
information in three python variables awailable in the empy template.
These are:
* ``file_name_in`` (String) Filename of the source .msg /.srv file
* ``spec`` (msggen.MsgSpec) Parsed specification of the .msg/.srv file
* ``md5sum`` (String) MD5Sum of the msg/srv
See https://github.com/ros/gencpp/blob/master/scripts/msg.h.template
and https://github.com/ros/gencpp/blob/master/scripts/srv.h.template
for example template files.
If the language requires a common file to exists for all the generated
source code files (Such as __init__.py for python) it is possible to
specify a ``module_template_map``. See
https://github.com/ros/genpybindings/blob/master/scripts/module.cpp.template
for example of this.
Catkin (fuerte)
~~~~~~~~~~~~~~~
Each language is identified by a name which must be specified in the stack.xml file.
In catkin fuerte, message generators declared their contribution in the stack.xml file.
The example entry for the generator for C++ is::
<message_generator>cpp</message_generator>
The project name for the generator with identifier ``X`` should be ``genX``.
Catkin (groovy)
~~~~~~~~~~~~~~~
In catkin groovy, message generators declared their contribution in the package.xml file::
<message_generator>cpp</message_generator>
Providing cmake code to catkin
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Generator packages define several macros (below), and use catkin
mechanisms to make the definitions of these macros available, see
``catkin_package``. catkin will generate calls to them for
* each message
* each service
* once for the overall package
For a generator called ``X``, in a package called ``genX``:
.. cmake:macro:: _generate_msg_X(PACKAGE MESSAGE IFLAGS MSG_DEPS OUTDIR)
:param PACKAGE: name of package that the generated message MESSAGE
is found in.
:param MESSAGE: full path to ``.msg`` file
:param IFLAGS: a list of flags in ``-I<package>:/path`` format
:param MSG_DEPS: a list of ``.msg`` files on which this message depends
:param OUTDIR: destination directory for generated files
There are two other macros, ``_generate_srv_X``,
.. cmake:macro:: _generate_srv_X(PACKAGE SERVICE IFLAGS MSG_DEPS OUTDIR)
:param PACKAGE: name of package that the generated message MESSAGE
is found in.
:param SERVICE: full path to ``.srv`` file
:param IFLAGS: a list of flags in ``-I<package>:/path`` format
:param MSG_DEPS: a list of ``.msg`` files on which this message
depends
:param OUTDIR: destination directory for generated files
and
.. cmake:macro:: _generate_module_X(PACKAGE OUTDIR GENERATED_FILES)
:param PACKAGE: name of package
:param OUTDIR: destination directory
:param GENERATED_FILES: Files that were generated (from messages
and services) for this package. Usually
used to pass to the ``DEPENDS`` option of
cmake's ``add_custom_command()``
Generate any "module" code necessary, e.g. ``__init__.py`` for
python or ``module.cpp`` for boost.python bindings.
Examples
~~~~~~~~
Example projects that use this infrastructure are ``gencpp``,
``genpy``, and ``genpybindings``, all found in the github repositories
at http://github.com/ros.

View File

@ -0,0 +1,21 @@
.. _index:
genmsg: generating code from ros .msg format
=============================================
Project ``genmsg`` exists in order to decouple code generation from
``.msg`` & ``.srv`` format files from the parsing of these files and
from impementation details of the build system (project directory
layout, existence or nonexistence of utilities like ``rospack``,
values of environment variables such as ``ROS_PACKAGE_PATH``):
i.e. none of these are required to be set in any particular way.
.. toctree::
usermacros
python_api
developer
Code generators may not use any information other than what is
provided on the commandline.

View File

@ -0,0 +1,19 @@
genmsg Python API
=================
.. module:: genmsg
Classes
-------
.. autoclass:: MsgSpec
:members:
.. autoclass:: SrvSpec
:members:
.. autoclass:: Constant
:members:
.. autoclass:: Field
:members:

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.5 KiB

View File

@ -0,0 +1,40 @@
User macro reference
====================
.. cmake:macro:: add_message_files(DIRECTORY dir FILES file1 [file2...] [PACKAGE pkgname] [NOINSTALL])
:param DIRECTORY: Directory containing messages. May be absolute or
relative to ``CMAKE_CURRENT_SOURCE_DIR``.
:param FILES: Files containing messages, relative to `msgdir`
:param PACKAGE: Optional alternate packagename (if the current project doesn't match the
desired namespace for the messages)
:param NOINSTALL: Do not automatically install the messages to the package's share/ directory.
Register the listed files as requiring message generation and installation.
.. cmake:macro:: add_service_files(DIRECTORY dir FILES file1 [file2...] [PACKAGE pkgname] [NOINSTALL])
Same as add_message_files... but for services.
.. cmake:macro:: generate_messages(DEPENDENCIES deps [LANGS lang1 lang2...])
:param DEPENDENCIES: Names of packages containing messages
contained by messages in the current package. Got it? i.e. if
one of our messages contains std_msgs.Header, ``std_msgs``
should appear in this list.
:param LANGS: Restrict generation to the listed languages.
Triggers the generation of message generation targets. i.e. in
project ``foo`` with generators ``gencpp`` and ``genpy`` accessible
in the workspace, triggers creation of targets ``foo_gencpp`` and
``foo_genpy``.
Now, if your code does depend on generated messages you need to add a dependency.
E.g. if you target foo depends on the C++ messages of your current bar project, you need to add:
``add_dependencies(foo bar_gencpp)``
(the ``bar_cpp`` target is automatically created when you generate messages)

View File

@ -0,0 +1,24 @@
<?xml version="1.0"?>
<package>
<name>genmsg</name>
<version>0.5.6</version>
<description>
Standalone Python library for generating ROS message and service data structures for various languages.
</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<license>BSD</license>
<url type="website">http://www.ros.org/wiki/genmsg</url>
<url type="bugtracker">https://github.com/ros/genmsg/issues</url>
<url type="repository">https://github.com/ros/genmsg</url>
<author>Troy Straszheim</author>
<author>Morten Kjaergaard</author>
<author>Ken Conley</author>
<buildtool_depend version_gte="0.5.74">catkin</buildtool_depend>
<export>
<rosdoc config="rosdoc.yaml"/>
</export>
</package>

View File

@ -0,0 +1,2 @@
- builder: sphinx
sphinx_root_dir: doc

View File

@ -0,0 +1,69 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2014, Open Source Robotics Foundation, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Open Source Robotics Foundation, Inc. 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 OWNER 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.
from __future__ import print_function
import os
import sys
from genmsg import EXT_MSG, EXT_SRV, MsgContext
from genmsg.gentools import compute_full_type_name
from genmsg.msg_loader import load_msg_from_file, load_srv_from_file
from genmsg.msgs import bare_msg_type, is_builtin, resolve_type
pkg_name = sys.argv[1]
msg_file = sys.argv[2]
deps = sys.argv[3].split(':') if len(sys.argv) > 3 else []
msg_context = MsgContext.create_default()
full_type_name = compute_full_type_name(pkg_name, os.path.basename(msg_file))
if msg_file.endswith(EXT_MSG):
spec = load_msg_from_file(msg_context, msg_file, full_type_name)
unresolved_types = spec.types
elif msg_file.endswith(EXT_SRV):
spec = load_srv_from_file(msg_context, msg_file, full_type_name)
unresolved_types = spec.request.types + spec.response.types
else:
print("Processing file: '%s' - unknown file extension" % msg_file, file=sys.stderr)
sys.exit(1)
package_context = spec.package
for unresolved_type in unresolved_types:
bare_type = bare_msg_type(unresolved_type)
resolved_type = resolve_type(bare_type, package_context)
if not is_builtin(resolved_type) and resolved_type not in deps:
print("The dependencies of the message/service '%s' have changed. Please rerun cmake." % spec.full_name, file=sys.stderr)
sys.exit(1)

View File

@ -0,0 +1,11 @@
#!/usr/bin/env python
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
d = generate_distutils_setup(
packages=['genmsg'],
package_dir={'': 'src'}
)
setup(**d)

View File

@ -0,0 +1,40 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
from . base import EXT_MSG, EXT_SRV, SEP, log, plog, InvalidMsgSpec, log_verbose, MsgGenerationException
from . gentools import compute_md5, compute_full_text, compute_md5_text
from . names import resource_name_base, package_resource_name, is_legal_resource_base_name, \
resource_name_package, resource_name, is_legal_resource_name
from . msgs import HEADER, TIME, DURATION, MsgSpec, Constant, Field
from . msg_loader import MsgNotFound, MsgContext, load_depends, load_msg_by_type, load_srv_by_type
from . srvs import SrvSpec

View File

@ -0,0 +1,75 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
from __future__ import print_function
import os, sys
SEP = '/'
MSG_DIR = 'msg'
SRV_DIR = 'srv'
EXT_MSG = '.msg'
EXT_SRV = '.srv'
## character that designates a constant assignment rather than a field
CONSTCHAR = '='
COMMENTCHAR = '#'
IODELIM = '---'
verbose = False
import inspect, pprint
def log_verbose(value):
global verbose
verbose = value
def log(*args):
global verbose
if verbose:
print("%s:%d" % inspect.stack()[1][1:3], file=sys.stderr)
print(' '.join([str(x) for x in args]), file=sys.stderr)
def plog(msg, obj):
if verbose:
print("%s:%d" % inspect.stack()[1][1:3], file=sys.stderr)
print(msg, " ", file=sys.stderr)
pprint.pprint(obj, file=sys.stderr)
class InvalidMsgSpec(Exception):
pass
class MsgGenerationException(Exception):
pass

View File

@ -0,0 +1,41 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
def includepath_to_dict(includepath):
search_path = {}
if includepath:
for path in includepath:
key = path[:path.find(':')]
value = path[path.find(':')+1:]
if value:
search_path.setdefault(key, []).append(value)
return search_path

View File

@ -0,0 +1,94 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
import os
import genmsg.msg_loader
import genmsg
# pkg_name - string
# msg_file - string full path
# search_paths - dict of {'pkg':'msg_dir'}
def find_msg_dependencies_with_type(pkg_name, msg_file, search_paths):
# Read and parse the source msg file
msg_context = genmsg.msg_loader.MsgContext.create_default()
full_type_name = genmsg.gentools.compute_full_type_name(pkg_name, os.path.basename(msg_file))
spec = genmsg.msg_loader.load_msg_from_file(msg_context, msg_file, full_type_name)
try:
genmsg.msg_loader.load_depends(msg_context, spec, search_paths)
except genmsg.InvalidMsgSpec as e:
raise genmsg.MsgGenerationException("Cannot read .msg for %s: %s"%(full_type_name, str(e)))
deps = set()
for dep_type_name in msg_context.get_all_depends(full_type_name):
deps.add((dep_type_name, msg_context.get_file(dep_type_name)))
return list(deps)
def find_msg_dependencies(pkg_name, msg_file, search_paths):
deps = find_msg_dependencies_with_type(pkg_name, msg_file, search_paths)
return [d[1] for d in deps]
def find_srv_dependencies_with_type(pkg_name, msg_file, search_paths):
# Read and parse the source msg file
msg_context = genmsg.msg_loader.MsgContext.create_default()
full_type_name = genmsg.gentools.compute_full_type_name(pkg_name, os.path.basename(msg_file))
spec = genmsg.msg_loader.load_srv_from_file(msg_context, msg_file, full_type_name)
try:
genmsg.msg_loader.load_depends(msg_context, spec, search_paths)
except genmsg.InvalidMsgSpec as e:
raise genmsg.MsgGenerationException("Cannot read .msg for %s: %s"%(full_type_name, str(e)))
deps = set()
for dep_type_name in msg_context.get_all_depends(spec.request.full_name):
deps.add((dep_type_name, msg_context.get_file(dep_type_name)))
for dep_type_name in msg_context.get_all_depends(spec.response.full_name):
deps.add((dep_type_name, msg_context.get_file(dep_type_name)))
return list(deps)
def find_srv_dependencies(pkg_name, msg_file, search_paths):
deps = find_srv_dependencies_with_type(pkg_name, msg_file, search_paths)
return [d[1] for d in deps]
#paths = {'std_msgs':'/u/mkjargaard/repositories/mkjargaard/dist-sandbox/std_msgs/msg'}
#file = '/u/mkjargaard/repositories/mkjargaard/dist-sandbox/quux_msgs/msg/QuuxString.msg'
#find_msg_dependencies('quux_msgs', file, paths)

View File

@ -0,0 +1,175 @@
#! /usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
"""
Library for supporting message and service generation for all ROS
client libraries. This is mainly responsible for calculating the
md5sums and message definitions of classes.
"""
# NOTE: this should not contain any rospy-specific code. The rospy
# generator library is rospy.genpy.
import sys
import hashlib
try:
from cStringIO import StringIO # Python 2.x
except ImportError:
from io import StringIO # Python 3.x
from . import msgs
from .msgs import InvalidMsgSpec, MsgSpec, bare_msg_type, is_builtin
from .msg_loader import load_depends
from .srvs import SrvSpec
from . import names
from . import base
def compute_md5_text(msg_context, spec):
"""
Compute the text used for md5 calculation. MD5 spec states that we
removes comments and non-meaningful whitespace. We also strip
packages names from type names. For convenience sake, constants are
reordered ahead of other declarations, in the order that they were
originally defined.
:returns: text for ROS MD5-processing, ``str``
"""
package = spec.package
buff = StringIO()
for c in spec.constants:
buff.write("%s %s=%s\n"%(c.type, c.name, c.val_text))
for type_, name in zip(spec.types, spec.names):
msg_type = bare_msg_type(type_)
# md5 spec strips package names
if is_builtin(msg_type):
buff.write("%s %s\n"%(type_, name))
else:
# recursively generate md5 for subtype. have to build up
# dependency representation for subtype in order to
# generate md5
sub_pkg, _ = names.package_resource_name(msg_type)
sub_pkg = sub_pkg or package
sub_spec = msg_context.get_registered(msg_type)
sub_md5 = compute_md5(msg_context, sub_spec)
buff.write("%s %s\n"%(sub_md5, name))
return buff.getvalue().strip() # remove trailing new line
def _compute_hash(msg_context, spec, hash):
"""
subroutine of compute_md5()
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: :class:`MsgSpec` to compute hash for.
:param hash: hash instance
"""
# accumulate the hash
# - root file
if isinstance(spec, MsgSpec):
hash.update(compute_md5_text(msg_context, spec).encode())
elif isinstance(spec, SrvSpec):
hash.update(compute_md5_text(msg_context, spec.request).encode())
hash.update(compute_md5_text(msg_context, spec.response).encode())
else:
raise Exception("[%s] is not a message or service"%spec)
return hash.hexdigest()
def compute_md5(msg_context, spec):
"""
Compute md5 hash for message/service
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: :class:`MsgSpec` to compute md5 for.
:returns: md5 hash, ``str``
"""
return _compute_hash(msg_context, spec, hashlib.md5())
## alias
compute_md5_v2 = compute_md5
def _unique_deps(dep_list):
uniques = []
for d in dep_list:
if d not in uniques:
uniques.append(d)
return uniques
def compute_full_text(msg_context, spec):
"""
Compute full text of message/service, including text of embedded
types. The text of the main msg/srv is listed first. Embedded
msg/srv files are denoted first by an 80-character '=' separator,
followed by a type declaration line,'MSG: pkg/type', followed by
the text of the embedded type.
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: :class:`MsgSpec` to compute full text for.
:returns: concatenated text for msg/srv file and embedded msg/srv types, ``str``
"""
buff = StringIO()
sep = '='*80+'\n'
# write the text of the top-level type
buff.write(spec.text)
buff.write('\n')
# append the text of the dependencies (embedded types). Can't use set() as we have to preserve order.
for d in _unique_deps(msg_context.get_all_depends(spec.full_name)):
buff.write(sep)
buff.write("MSG: %s\n"%d)
buff.write(msg_context.get_registered(d).text)
buff.write('\n')
# #1168: remove the trailing \n separator that is added by the concatenation logic
return buff.getvalue()[:-1]
def compute_full_type_name(package_name, file_name):
"""
Compute the full type name of message/service 'pkg/type'.
:param package_name: name of package file is in, ``str``
:file_name: name of the msg og srv file, ``str``
:returns: typename in format 'pkg/type'
:raises: :exc:`MsgGenerationException` if file_name ends with an unknown file extension
"""
# strip extension
for ext in (base.EXT_MSG, base.EXT_SRV):
if file_name.endswith(ext):
short_name = file_name[:-len(ext)]
break
else:
raise base.MsgGenerationException("Processing file: '%s' - unknown file extension"% (file_name))
return "%s/%s"%(package_name, short_name)

View File

@ -0,0 +1,484 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
from __future__ import print_function
"""
Loader for messages and :class:`MsgContext` that assumes a
dictionary-based search path scheme (keys are the package/namespace,
values are the paths). Compatible with ROS package system and other
possible layouts.
"""
import os
import sys
try:
from cStringIO import StringIO # Python 2.x
except ImportError:
from io import StringIO # Python 3.x
from . base import InvalidMsgSpec, log, SEP, COMMENTCHAR, CONSTCHAR, IODELIM, EXT_MSG, EXT_SRV
from . msgs import MsgSpec, TIME, TIME_MSG, DURATION, DURATION_MSG, HEADER, HEADER_FULL_NAME, \
is_builtin, is_valid_msg_field_name, is_valid_msg_type, bare_msg_type, is_valid_constant_type, \
Field, Constant, resolve_type
from . names import normalize_package_context, package_resource_name
from . srvs import SrvSpec
class MsgNotFound(Exception):
pass
def get_msg_file(package, base_type, search_path, ext=EXT_MSG):
"""
Determine the file system path for the specified ``.msg`` on
*search_path*.
:param package: name of package file is in, ``str``
:param base_type: type name of message, e.g. 'Point2DFloat32', ``str``
:param search_path: dictionary mapping message namespaces to a directory locations
:param ext: msg file extension. Override with EXT_SRV to search for services instead.
:returns: filesystem path of requested file, ``str``
:raises: :exc:`MsgNotFound` If message cannot be located.
"""
log("msg_file(%s, %s, %s)" % (package, base_type, str(search_path)))
if not isinstance(search_path, dict):
raise ValueError("search_path must be a dictionary of {namespace: dirpath}")
if not package in search_path:
raise MsgNotFound("Cannot locate message [%s]: unknown package [%s] on search path [%s]" \
% (base_type, package, search_path))
else:
for path_tmp in search_path[package]:
path = os.path.join(path_tmp, "%s%s"%(base_type, ext))
if os.path.isfile(path):
return path
raise MsgNotFound("Cannot locate message [%s] in package [%s] with paths [%s]"%
(base_type, package, str(search_path[package])))
def get_srv_file(package, base_type, search_path):
"""
Determine the file system path for the specified .srv on path.
:param package: name of package ``.srv`` file is in, ``str``
:param base_type: type name of service, e.g. 'Empty', ``str``
:param search_path: dictionary mapping message namespaces to a directory locations
:returns: file path of ``.srv`` file in specified package, ``str``
:raises: :exc:`MsgNotFound` If service file cannot be located.
"""
return get_msg_file(package, base_type, search_path, ext=EXT_SRV)
def load_msg_by_type(msg_context, msg_type, search_path):
"""
Load message specification for specified type.
NOTE: this will register the message in the *msg_context*.
:param msg_context: :class:`MsgContext` for finding loaded dependencies
:param msg_type: relative or full message type.
:param search_path: dictionary mapping message namespaces to a directory locations
:returns: :class:`MsgSpec` instance, ``(str, MsgSpec)``
:raises: :exc:`MsgNotFound` If message cannot be located.
"""
log("load_msg_by_type(%s, %s)" % (msg_type, str(search_path)))
if not isinstance(search_path, dict):
raise ValueError("search_path must be a dictionary of {namespace: dirpath}")
if msg_type == HEADER:
msg_type = HEADER_FULL_NAME
package_name, base_type = package_resource_name(msg_type)
file_path = get_msg_file(package_name, base_type, search_path)
log("file_path", file_path)
spec = load_msg_from_file(msg_context, file_path, msg_type)
msg_context.set_file(msg_type, file_path)
return spec
def load_srv_by_type(msg_context, srv_type, search_path):
"""
Load service specification for specified type.
NOTE: services are *never* registered in a :class:`MsgContext`.
:param msg_context: :class:`MsgContext` for finding loaded dependencies
:param srv_type: relative or full message type.
:param search_path: dictionary mapping message namespaces to a directory locations
:returns: :class:`MsgSpec` instance, ``(str, MsgSpec)``
:raises: :exc:`MsgNotFound` If message cannot be located.
"""
log("load_srv_by_type(%s, %s)" % (srv_type, str(search_path)))
if not isinstance(search_path, dict):
raise ValueError("search_path must be a dictionary of {namespace: dirpath}")
package_name, base_type = package_resource_name(srv_type)
file_path = get_srv_file(package_name, base_type, search_path)
log("file_path", file_path)
return load_srv_from_file(msg_context, file_path, srv_type)
def convert_constant_value(field_type, val):
"""
Convert constant value declaration to python value. Does not do
type-checking, so ValueError or other exceptions may be raised.
:param field_type: ROS field type, ``str``
:param val: string representation of constant, ``str``
:raises: :exc:`ValueError` If unable to convert to python representation
:raises: :exc:`InvalidMsgSpec` If value exceeds specified integer width
"""
if field_type in ['float32','float64']:
return float(val)
elif field_type in ['string']:
return val.strip() #string constants are always stripped
elif field_type in ['int8', 'uint8', 'int16','uint16','int32','uint32','int64','uint64', 'char', 'byte']:
# bounds checking
bits = [('int8', 8), ('uint8', 8), ('int16', 16),('uint16', 16),\
('int32', 32),('uint32', 32), ('int64', 64),('uint64', 64),\
('byte', 8), ('char', 8)]
b = [b for t, b in bits if t == field_type][0]
import math
if field_type[0] == 'u' or field_type == 'char':
lower = 0
upper = int(math.pow(2, b)-1)
else:
upper = int(math.pow(2, b-1)-1)
lower = -upper - 1 #two's complement min
val = int(val) #python will autocast to long if necessary
if val > upper or val < lower:
raise InvalidMsgSpec("cannot coerce [%s] to %s (out of bounds)"%(val, field_type))
return val
elif field_type == 'bool':
# TODO: need to nail down constant spec for bool
return True if eval(val) else False
raise InvalidMsgSpec("invalid constant type: [%s]"%field_type)
def _load_constant_line(orig_line):
"""
:raises: :exc:`InvalidMsgSpec`
"""
clean_line = _strip_comments(orig_line)
line_splits = [s for s in [x.strip() for x in clean_line.split(" ")] if s] #split type/name, filter out empties
field_type = line_splits[0]
if not is_valid_constant_type(field_type):
raise InvalidMsgSpec("%s is not a legal constant type"%field_type)
if field_type == 'string':
# strings contain anything to the right of the equals sign, there are no comments allowed
idx = orig_line.find(CONSTCHAR)
name = orig_line[orig_line.find(' ')+1:idx]
val = orig_line[idx+1:]
else:
line_splits = [x.strip() for x in ' '.join(line_splits[1:]).split(CONSTCHAR)] #resplit on '='
if len(line_splits) != 2:
raise InvalidMsgSpec("Invalid constant declaration: %s"%l)
name = line_splits[0]
val = line_splits[1]
try:
val_converted = convert_constant_value(field_type, val)
except Exception as e:
raise InvalidMsgSpec("Invalid constant value: %s"%e)
return Constant(field_type, name, val_converted, val.strip())
def _load_field_line(orig_line, package_context):
"""
:returns: (field_type, name) tuple, ``(str, str)``
:raises: :exc:`InvalidMsgSpec`
"""
#log("_load_field_line", orig_line, package_context)
clean_line = _strip_comments(orig_line)
line_splits = [s for s in [x.strip() for x in clean_line.split(" ")] if s] #split type/name, filter out empties
if len(line_splits) != 2:
raise InvalidMsgSpec("Invalid declaration: %s"%(orig_line))
field_type, name = line_splits
if not is_valid_msg_field_name(name):
raise InvalidMsgSpec("%s is not a legal message field name"%name)
if not is_valid_msg_type(field_type):
raise InvalidMsgSpec("%s is not a legal message field type"%field_type)
if package_context and not SEP in field_type:
if field_type == HEADER:
field_type = HEADER_FULL_NAME
elif not is_builtin(bare_msg_type(field_type)):
field_type = "%s/%s"%(package_context, field_type)
elif field_type == HEADER:
field_type = HEADER_FULL_NAME
return field_type, name
def _strip_comments(line):
return line.split(COMMENTCHAR)[0].strip() #strip comments
def load_msg_from_string(msg_context, text, full_name):
"""
Load message specification from a string.
NOTE: this will register the message in the *msg_context*.
:param msg_context: :class:`MsgContext` for finding loaded dependencies
:param text: .msg text , ``str``
:returns: :class:`MsgSpec` specification
:raises: :exc:`InvalidMsgSpec` If syntax errors or other problems are detected in file
"""
log("load_msg_from_string", full_name)
package_name, short_name = package_resource_name(full_name)
types = []
names = []
constants = []
for orig_line in text.split('\n'):
clean_line = _strip_comments(orig_line)
if not clean_line:
continue #ignore empty lines
if CONSTCHAR in clean_line:
constants.append(_load_constant_line(orig_line))
else:
field_type, name = _load_field_line(orig_line, package_name)
types.append(field_type)
names.append(name)
spec = MsgSpec(types, names, constants, text, full_name, package_name)
msg_context.register(full_name, spec)
return spec
def load_msg_from_file(msg_context, file_path, full_name):
"""
Convert the .msg representation in the file to a :class:`MsgSpec` instance.
NOTE: this will register the message in the *msg_context*.
:param file_path: path of file to load from, ``str``
:returns: :class:`MsgSpec` instance
:raises: :exc:`InvalidMsgSpec`: if syntax errors or other problems are detected in file
"""
log("Load spec from", file_path)
with open(file_path, 'r') as f:
text = f.read()
try:
return load_msg_from_string(msg_context, text, full_name)
except InvalidMsgSpec as e:
raise InvalidMsgSpec('%s: %s'%(file_path, e))
def load_msg_depends(msg_context, spec, search_path):
"""
Add the list of message types that spec depends on to depends.
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: message to compute dependencies for, :class:`MsgSpec`/:class:`SrvSpec`
:param search_path: dictionary mapping message namespaces to a directory locations
:param deps: for recursion use only, do not set
:returns: list of dependency names, ``[str]``
:raises: :exc:`MsgNotFound` If dependency cannot be located.
"""
package_context = spec.package
log("load_msg_depends <spec>", spec.full_name, package_context)
depends = []
# Iterate over each field, loading as necessary
for unresolved_type in spec.types:
bare_type = bare_msg_type(unresolved_type)
resolved_type = resolve_type(bare_type, package_context)
if is_builtin(resolved_type):
continue
# Retrieve the MsgSpec instance of the field
if msg_context.is_registered(resolved_type):
depspec = msg_context.get_registered(resolved_type)
else:
# load and register on demand
depspec = load_msg_by_type(msg_context, resolved_type, search_path)
msg_context.register(resolved_type, depspec)
# Update dependencies
depends.append(resolved_type)
# - check to see if we have compute dependencies of field
dep_dependencies = msg_context.get_depends(resolved_type)
if dep_dependencies is None:
load_msg_depends(msg_context, depspec, search_path)
assert spec.full_name, "MsgSpec must have a properly set full name"
msg_context.set_depends(spec.full_name, depends)
# have to copy array in order to prevent inadvertent mutation (we've stored this list in set_dependencies)
return depends[:]
def load_depends(msg_context, spec, msg_search_path):
"""
Compute dependencies of *spec* and load their MsgSpec dependencies
into *msg_context*.
NOTE: *msg_search_path* is only for finding .msg files. ``.srv``
files have a separate and distinct search path. As services
cannot depend on other services, it is not necessary to provide
the srv search path here.
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: :class:`MsgSpec` or :class:`SrvSpec` instance to load dependencies for.
:param msg_search_path: dictionary mapping message namespaces to a directory locations.
:raises: :exc:`MsgNotFound` If dependency cannot be located.
"""
if isinstance(spec, MsgSpec):
return load_msg_depends(msg_context, spec, msg_search_path)
elif isinstance(spec, SrvSpec):
depends = load_msg_depends(msg_context, spec.request, msg_search_path)
depends.extend(load_msg_depends(msg_context, spec.response, msg_search_path))
return depends
else:
raise ValueError("spec does not appear to be a message or service")
class MsgContext(object):
"""
Context object for storing :class:`MsgSpec` instances and related
metadata.
NOTE: All APIs work on :class:`MsgSpec` instance information.
Thus, for services, there is information for the request and
response messages, but there is no direct information about the
:class:`SrvSpec` instance.
"""
def __init__(self):
self._registered_packages = {}
self._files = {}
self._dependencies = {}
def set_file(self, full_msg_type, file_path):
self._files[full_msg_type] = file_path
def get_file(self, full_msg_type):
return self._files.get(full_msg_type, None)
def set_depends(self, full_msg_type, dependencies):
"""
:param dependencies: direct first order
dependencies for *full_msg_type*
"""
log("set_depends", full_msg_type, dependencies)
self._dependencies[full_msg_type] = dependencies
def get_depends(self, full_msg_type):
"""
:returns: List of dependencies for *full_msg_type*,
only first order dependencies
"""
return self._dependencies.get(full_msg_type, None)
def get_all_depends(self, full_msg_type):
all_deps = []
depends = self.get_depends(full_msg_type)
if depends is None:
raise KeyError(full_msg_type)
for d in depends:
all_deps.extend([d])
all_deps.extend(self.get_all_depends(d))
return all_deps
@staticmethod
def create_default():
msg_context = MsgContext()
# register builtins (needed for serialization). builtins have no package.
load_msg_from_string(msg_context, TIME_MSG, TIME)
load_msg_from_string(msg_context, DURATION_MSG, DURATION)
return msg_context
def register(self, full_msg_type, msgspec):
full_msg_type = bare_msg_type(full_msg_type)
package, base_type = package_resource_name(full_msg_type)
if package not in self._registered_packages:
self._registered_packages[package] = {}
self._registered_packages[package][base_type] = msgspec
def is_registered(self, full_msg_type):
"""
:param full_msg_type: Fully resolve message type
:param default_package: default package namespace to resolve
in. May be ignored by special types (e.g. time/duration).
:returns: ``True`` if :class:`MsgSpec` instance has been loaded for the requested type.
"""
full_msg_type = bare_msg_type(full_msg_type)
package, base_type = package_resource_name(full_msg_type)
if package in self._registered_packages:
return base_type in self._registered_packages[package]
else:
return False
def get_registered(self, full_msg_type):
"""
:raises: :exc:`KeyError` If not registered
"""
full_msg_type = bare_msg_type(full_msg_type)
if self.is_registered(full_msg_type):
package, base_type = package_resource_name(full_msg_type)
return self._registered_packages[package][base_type]
else:
raise KeyError(full_msg_type)
def __str__(self):
return str(self._registered_packages)
def load_srv_from_string(msg_context, text, full_name):
"""
Load :class:`SrvSpec` from the .srv file.
:param msg_context: :class:`MsgContext` instance to load request/response messages into.
:param text: .msg text , ``str``
:param package_name: context to use for msg type name, i.e. the package name,
or '' to use local naming convention. ``str``
:returns: :class:`SrvSpec` instance
:raises :exc:`InvalidMsgSpec` If syntax errors or other problems are detected in file
"""
text_in = StringIO()
text_out = StringIO()
accum = text_in
for l in text.split('\n'):
l = l.split(COMMENTCHAR)[0].strip() #strip comments
if l.startswith(IODELIM): #lenient, by request
accum = text_out
else:
accum.write(l+'\n')
# create separate MsgSpec objects for each half of file
msg_in = load_msg_from_string(msg_context, text_in.getvalue(), '%sRequest'%(full_name))
msg_out = load_msg_from_string(msg_context, text_out.getvalue(), '%sResponse'%(full_name))
return SrvSpec(msg_in, msg_out, text, full_name)
def load_srv_from_file(msg_context, file_path, full_name):
"""
Convert the .srv representation in the file to a :class:`SrvSpec` instance.
:param msg_context: :class:`MsgContext` instance to load request/response messages into.
:param file_name: name of file to load from, ``str``
:returns: :class:`SrvSpec` instance
:raise: :exc:`InvalidMsgSpec` If syntax errors or other problems are detected in file
"""
log("Load spec from %s %s\n"%(file_path, full_name))
with open(file_path, 'r') as f:
text = f.read()
spec = load_srv_from_string(msg_context, text, full_name)
msg_context.set_file('%sRequest'%(full_name), file_path)
msg_context.set_file('%sResponse'%(full_name), file_path)
return spec

View File

@ -0,0 +1,349 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
from __future__ import print_function
"""
ROS msg library for Python
Implements: U{http://ros.org/wiki/msg}
"""
import os
import sys
from . base import InvalidMsgSpec, EXT_MSG, MSG_DIR, SEP, log
from . names import is_legal_resource_name, is_legal_resource_base_name, package_resource_name, resource_name
#TODOXXX: unit test
def bare_msg_type(msg_type):
"""
Compute the bare data type, e.g. for arrays, get the underlying array item type
:param msg_type: ROS msg type (e.g. 'std_msgs/String'), ``str``
:returns: base type, ``str``
"""
if msg_type is None:
return None
if '[' in msg_type:
return msg_type[:msg_type.find('[')]
return msg_type
def resolve_type(msg_type, package_context):
"""
Resolve type name based on current package context.
NOTE: in ROS Diamondback, 'Header' resolves to
'std_msgs/Header'. In previous releases, it resolves to
'roslib/Header' (REP 100).
e.g.::
resolve_type('String', 'std_msgs') -> 'std_msgs/String'
resolve_type('String[]', 'std_msgs') -> 'std_msgs/String[]'
resolve_type('std_msgs/String', 'foo') -> 'std_msgs/String'
resolve_type('uint16', 'std_msgs') -> 'uint16'
resolve_type('uint16[]', 'std_msgs') -> 'uint16[]'
"""
bt = bare_msg_type(msg_type)
if bt in BUILTIN_TYPES:
return msg_type
elif bt == HEADER:
return HEADER_FULL_NAME
elif SEP in msg_type:
return msg_type
else:
return "%s%s%s"%(package_context, SEP, msg_type)
#NOTE: this assumes that we aren't going to support multi-dimensional
def parse_type(msg_type):
"""
Parse ROS message field type
:param msg_type: ROS field type, ``str``
:returns: base_type, is_array, array_length, ``(str, bool, int)``
:raises: :exc:`ValueError` If *msg_type* cannot be parsed
"""
if not msg_type:
raise ValueError("Invalid empty type")
if '[' in msg_type:
var_length = msg_type.endswith('[]')
splits = msg_type.split('[')
if len(splits) > 2:
raise ValueError("Currently only support 1-dimensional array types: %s"%msg_type)
if var_length:
return msg_type[:-2], True, None
else:
try:
length = int(splits[1][:-1])
return splits[0], True, length
except ValueError:
raise ValueError("Invalid array dimension: [%s]"%splits[1][:-1])
else:
return msg_type, False, None
################################################################################
# name validation
def is_valid_msg_type(x):
"""
:returns: True if the name is a syntatically legal message type name, ``bool``
"""
if not x or len(x) != len(x.strip()):
return False
base = bare_msg_type(x)
if not is_legal_resource_name(base):
return False
#parse array indices
x = x[len(base):]
state = 0
i = 0
for c in x:
if state == 0:
if c != '[':
return False
state = 1 #open
elif state == 1:
if c == ']':
state = 0 #closed
else:
try:
int(c)
except:
return False
return state == 0
def is_valid_constant_type(x):
"""
:returns: ``True`` if the name is a legal constant type. Only simple types are allowed, ``bool``
"""
return x in PRIMITIVE_TYPES
def is_valid_msg_field_name(x):
"""
:returns: ``True`` if the name is a syntatically legal message field name, ``bool``
"""
return is_legal_resource_base_name(x)
# msg spec representation ##########################################
class Constant(object):
"""
Container class for holding a Constant declaration
Attributes:
- ``type``
- ``name``
- ``val``
- ``val_text``
"""
__slots__ = ['type', 'name', 'val', 'val_text']
def __init__(self, type_, name, val, val_text):
"""
:param type_: constant type, ``str``
:param name: constant name, ``str``
:param val: constant value, ``str``
:param val_text: Original text definition of *val*, ``str``
"""
if type is None or name is None or val is None or val_text is None:
raise ValueError('Constant must have non-None parameters')
self.type = type_
self.name = name.strip() #names are always stripped of whitespace
self.val = val
self.val_text = val_text
def __eq__(self, other):
if not isinstance(other, Constant):
return False
return self.type == other.type and self.name == other.name and self.val == other.val
def __repr__(self):
return "%s %s=%s"%(self.type, self.name, self.val)
def __str__(self):
return "%s %s=%s"%(self.type, self.name, self.val)
class Field(object):
"""
Container class for storing information about a single field in a MsgSpec
Attributes:
- ``name``
- ``type``
- ``base_type``
- ``is_array``
- ``array_len``
- ``is_builtin``
- ``is_header``
"""
def __init__(self, name, type):
self.name = name
self.type = type
(self.base_type, self.is_array, self.array_len) = parse_type(type)
self.is_header = is_header_type(self.type)
self.is_builtin = is_builtin(self.base_type)
def __eq__(self, other):
if not isinstance(other, Field):
return False
else:
return self.name == other.name and \
self.type == other.type
def __repr__(self):
return "[%s, %s, %s, %s, %s]"%(self.name, self.type, self.base_type, self.is_array, self.array_len)
class MsgSpec(object):
"""
Container class for storing loaded msg description files. Field
types and names are stored in separate lists with 1-to-1
correspondence. MsgSpec can also return an md5 of the source text.
"""
def __init__(self, types, names, constants, text, full_name, package = '', short_name = ''):
"""
:param types: list of field types, in order of declaration, ``[str]]``
:param names: list of field names, in order of declaration, ``[str]]``
:param constants: List of :class:`Constant` declarations, ``[Constant]``
:param text: text of declaration, ``str`
:raises: :exc:`InvalidMsgSpec` If spec is invalid (e.g. fields with the same name)
"""
alt_package, alt_short_name = package_resource_name(full_name)
if not package:
package = alt_package
if not short_name:
short_name = alt_short_name
self.types = types
if len(set(names)) != len(names):
raise InvalidMsgSpec("Duplicate field names in message: %s"%names)
self.names = names
self.constants = constants
assert len(self.types) == len(self.names), "len(%s) != len(%s)"%(self.types, self.names)
#Header.msg support
if (len(self.types)):
self.header_present = self.types[0] == HEADER_FULL_NAME and self.names[0] == 'header'
else:
self.header_present = False
self.text = text
self.full_name = full_name
self.short_name = short_name
self.package = package
try:
self._parsed_fields = [Field(name, type) for (name, type) in zip(self.names, self.types)]
except ValueError as e:
raise InvalidMsgSpec("invalid field: %s"%(e))
def fields(self):
"""
:returns: zip list of types and names (e.g. [('int32', 'x'), ('int32', 'y')], ``[(str,str),]``
"""
return list(zip(self.types, self.names)) #py3k
def parsed_fields(self):
"""
:returns: list of :class:`Field` classes, ``[Field,]``
"""
return self._parsed_fields
def has_header(self):
"""
:returns: ``True`` if msg decription contains a 'Header header'
declaration at the beginning, ``bool``
"""
return self.header_present
def __eq__(self, other):
if not other or not isinstance(other, MsgSpec):
return False
return self.types == other.types and self.names == other.names and \
self.constants == other.constants and self.text == other.text and \
self.full_name == other.full_name and self.short_name == other.short_name and \
self.package == other.package
def __ne__(self, other):
if not other or not isinstance(other, MsgSpec):
return True
return not self.__eq__(other)
def __repr__(self):
if self.constants:
return "MsgSpec[%s, %s, %s]"%(repr(self.constants), repr(self.types), repr(self.names))
else:
return "MsgSpec[%s, %s]"%(repr(self.types), repr(self.names))
def __str__(self):
return self.text
# .msg file routines ##############################################################
# adjustable constants, in case we change our minds
HEADER = 'Header'
TIME = 'time'
DURATION = 'duration'
HEADER_FULL_NAME = 'std_msgs/Header'
def is_header_type(msg_type):
"""
:param msg_type: message type name, ``str``
:returns: ``True`` if *msg_type* refers to the ROS Header type, ``bool``
"""
# for backwards compatibility, include roslib/Header. REP 100
return msg_type in [HEADER, HEADER_FULL_NAME, 'roslib/Header']
# time and duration types are represented as aggregate data structures
# for the purposes of serialization from the perspective of
# roslib.msgs. genmsg_py will do additional special handling is required
# to convert them into rospy.msg.Time/Duration instances.
## time as msg spec. time is unsigned
TIME_MSG = "uint32 secs\nuint32 nsecs"
## duration as msg spec. duration is just like time except signed
DURATION_MSG = "int32 secs\nint32 nsecs"
## primitive types are those for which we allow constants, i.e. have primitive representation
PRIMITIVE_TYPES = ['int8','uint8','int16','uint16','int32','uint32','int64','uint64','float32','float64',
'string',
'bool',
# deprecated:
'char','byte']
BUILTIN_TYPES = PRIMITIVE_TYPES + [TIME, DURATION]
def is_builtin(msg_type_name):
"""
:param msg_type_name: name of message type, ``str``
:returns: True if msg_type_name is a builtin/primitive type, ``bool``
"""
return msg_type_name in BUILTIN_TYPES

View File

@ -0,0 +1,145 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
PRN_SEPARATOR = '/'
import re
def normalize_package_context(package_context):
package_context = package_context.strip()
while package_context.endswith(PRN_SEPARATOR):
package_context = package_context[:-1]
return package_context
#######################################################################
# RESOURCE NAMES
# resource names refer to entities in a file system
def resource_name(res_pkg_name, name, my_pkg=None):
"""
Convert package name + resource into a fully qualified resource name
@param res_pkg_name: name of package resource is located in
@type res_pkg_name: str
@param name: resource base name
@type name: str
@param my_pkg: name of package resource is being referred to
in. If specified, name will be returned in local form if
res_pkg_name is my_pkg
@type my_pkg: str
@return: name for resource
@rtype: str
"""
if res_pkg_name != my_pkg:
return res_pkg_name+PRN_SEPARATOR+name
return name
def resource_name_base(name):
"""
pkg/typeName -> typeName, typeName -> typeName
Convert fully qualified resource name into the package-less resource name
@param name: package resource name, e.g. 'std_msgs/String'
@type name: str
@return: resource name sans package-name scope
@rtype: str
"""
return name[name.rfind(PRN_SEPARATOR)+1:]
def resource_name_package(name):
"""
pkg/typeName -> pkg, typeName -> None
@param name: package resource name, e.g. 'std_msgs/String'
@type name: str
@return: package name of resource
@rtype: str
"""
if not PRN_SEPARATOR in name:
return None
return name[:name.find(PRN_SEPARATOR)]
def package_resource_name(name):
"""
Split a name into its package and resource name parts, e.g. 'std_msgs/String -> std_msgs, String'
@param name: package resource name, e.g. 'std_msgs/String'
@type name: str
@return: package name, resource name
@rtype: str
@raise ValueError: if name is invalid
"""
if PRN_SEPARATOR in name:
val = tuple(name.split(PRN_SEPARATOR))
if len(val) != 2:
raise ValueError("invalid name [%s]"%name)
else:
return val
else:
return '', name
################################################################################
# NAME VALIDATORS
#ascii char followed by (alphanumeric, _, /)
RESOURCE_NAME_LEGAL_CHARS_P = re.compile('^[A-Za-z][\w_\/]*$')
def is_legal_resource_name(name):
"""
Check if name is a legal ROS name for filesystem resources
(alphabetical character followed by alphanumeric, underscore, or
forward slashes). This constraint is currently not being enforced,
but may start getting enforced in later versions of ROS.
@param name: Name
@type name: str
"""
# resource names can be unicode due to filesystem
if name is None:
return False
m = RESOURCE_NAME_LEGAL_CHARS_P.match(name)
# '//' check makes sure there isn't double-slashes
return m is not None and m.group(0) == name and not '//' in name
BASE_RESOURCE_NAME_LEGAL_CHARS_P = re.compile('^[A-Za-z][\w_]*$') #ascii char followed by (alphanumeric, _)
def is_legal_resource_base_name(name):
"""
Validates that name is a legal resource base name. A base name has
no package context, e.g. "String".
"""
# resource names can be unicode due to filesystem
if name is None:
return False
m = BASE_RESOURCE_NAME_LEGAL_CHARS_P.match(name)
return m is not None and m.group(0) == name

View File

@ -0,0 +1,78 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
"""
ROS Service Description Language Spec
Implements http://ros.org/wiki/srv
"""
import os
import sys
from . names import is_legal_resource_name, is_legal_resource_base_name, package_resource_name, resource_name
class SrvSpec(object):
def __init__(self, request, response, text, full_name = '', short_name = '', package = ''):
alt_package, alt_short_name = package_resource_name(full_name)
if not package:
package = alt_package
if not short_name:
short_name = alt_short_name
self.request = request
self.response = response
self.text = text
self.full_name = full_name
self.short_name = short_name
self.package = package
def __eq__(self, other):
if not other or not isinstance(other, SrvSpec):
return False
return self.request == other.request and \
self.response == other.response and \
self.text == other.text and \
self.full_name == other.full_name and \
self.short_name == other.short_name and \
self.package == other.package
def __ne__(self, other):
if not other or not isinstance(other, SrvSpec):
return True
return not self.__eq__(other)
def __repr__(self):
return "SrvSpec[%s, %s]"%(repr(self.request), repr(self.response))

View File

@ -0,0 +1,216 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2011, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * 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.
# * Neither the name of Willow Garage, Inc. 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 OWNER 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.
## ROS Message generatation
##
##
import sys
import os
import em
import genmsg.command_line
import genmsg.msgs
import genmsg.msg_loader
import genmsg.gentools
# generate msg or srv files from a template file
# template_map of the form { 'template_file':'output_file'} output_file can contain @NAME@ which will be replaced by the message/service name
def _generate_from_spec(input_file, output_dir, template_dir, msg_context, spec, template_map, search_path):
md5sum = genmsg.gentools.compute_md5(msg_context, spec)
# precompute msg definition once
if isinstance(spec, genmsg.msgs.MsgSpec):
msg_definition = genmsg.gentools.compute_full_text(msg_context, spec)
# Loop over all files to generate
for template_file_name, output_file_name in template_map.items():
template_file = os.path.join(template_dir, template_file_name)
output_file = os.path.join(output_dir, output_file_name.replace("@NAME@", spec.short_name))
#print "generate_from_template %s %s %s" % (input_file, template_file, output_file)
ofile = open(output_file, 'w') #todo try
# Set dictionary for the generator interpreter
g = {
"file_name_in": input_file,
"spec": spec,
"md5sum": md5sum,
"search_path": search_path,
"msg_context": msg_context
}
if isinstance(spec, genmsg.msgs.MsgSpec):
g['msg_definition'] = msg_definition
# todo, reuse interpreter
interpreter = em.Interpreter(output=ofile, globals=g, options={em.RAW_OPT:True,em.BUFFERED_OPT:True})
if not os.path.isfile(template_file):
ofile.close()
os.remove(output_file)
raise RuntimeError("Template file %s not found in template dir %s" % (template_file_name, template_dir))
interpreter.file(open(template_file)) #todo try
interpreter.shutdown()
def _generate_msg_from_file(input_file, output_dir, template_dir, search_path, package_name, msg_template_dict):
# Read MsgSpec from .msg file
msg_context = genmsg.msg_loader.MsgContext.create_default()
full_type_name = genmsg.gentools.compute_full_type_name(package_name, os.path.basename(input_file))
spec = genmsg.msg_loader.load_msg_from_file(msg_context, input_file, full_type_name)
# Load the dependencies
genmsg.msg_loader.load_depends(msg_context, spec, search_path)
# Generate the language dependent msg file
_generate_from_spec(input_file,
output_dir,
template_dir,
msg_context,
spec,
msg_template_dict,
search_path)
def _generate_srv_from_file(input_file, output_dir, template_dir, search_path, package_name, srv_template_dict, msg_template_dict):
# Read MsgSpec from .srv.file
msg_context = genmsg.msg_loader.MsgContext.create_default()
full_type_name = genmsg.gentools.compute_full_type_name(package_name, os.path.basename(input_file))
spec = genmsg.msg_loader.load_srv_from_file(msg_context, input_file, full_type_name)
# Load the dependencies
genmsg.msg_loader.load_depends(msg_context, spec, search_path)
# Generate the language dependent srv file
_generate_from_spec(input_file,
output_dir,
template_dir,
msg_context,
spec,
srv_template_dict,
search_path)
# Generate the language dependent msg file for the srv request
_generate_from_spec(input_file,
output_dir,
template_dir,
msg_context,
spec.request,
msg_template_dict,
search_path)
# Generate the language dependent msg file for the srv response
_generate_from_spec(input_file,
output_dir,
template_dir,
msg_context,
spec.response,
msg_template_dict,
search_path)
# uniform interface for genering either srv or msg files
def generate_from_file(input_file, package_name, output_dir, template_dir, include_path, msg_template_dict, srv_template_dict):
# Normalize paths
input_file = os.path.abspath(input_file)
output_dir = os.path.abspath(output_dir)
# Create output dir
try:
os.makedirs(output_dir)
except OSError as e:
if e.errno != 17: # ignore file exists error
raise
# Parse include path dictionary
if( include_path ):
search_path = genmsg.command_line.includepath_to_dict(include_path)
else:
search_path = {}
# Generate the file(s)
if input_file.endswith(".msg"):
_generate_msg_from_file(input_file, output_dir, template_dir, search_path, package_name, msg_template_dict)
elif input_file.endswith(".srv"):
_generate_srv_from_file(input_file, output_dir, template_dir, search_path, package_name, srv_template_dict, msg_template_dict)
else:
assert False, "Uknown file extension for %s"%input_file
def generate_module(package_name, output_dir, template_dir, template_dict):
# Locate generate msg files
files = os.listdir(output_dir)
# Loop over all files to generate
for template_file_name, output_file_name in template_dict.items():
template_file = os.path.join(template_dir, template_file_name)
output_file = os.path.join(output_dir, output_file_name)
ofile = open(output_file, 'w') #todo try
# Set dictionary for the generator intepreter
g = dict(files=files,
package=package_name)
# todo, reuse interpreter
interpreter = em.Interpreter(output=ofile, options={em.RAW_OPT:True,em.BUFFERED_OPT:True})
interpreter.updateGlobals(g)
if not os.path.isfile(template_file):
ofile.close()
os.remove(output_file)
raise RuntimeError("Template file %s not found in template dir %s" % (template_file_name, template_dir))
interpreter.file(open(template_file)) #todo try
interpreter.shutdown()
# Uniform interface to support the standard command line options
def generate_from_command_line_options(argv, msg_template_dict, srv_template_dict, module_template_dict = {}):
from optparse import OptionParser
parser = OptionParser("[options] <srv file>")
parser.add_option("-p", dest='package',
help="ros package the generated msg/srv files belongs to")
parser.add_option("-o", dest='outdir',
help="directory in which to place output files")
parser.add_option("-I", dest='includepath',
help="include path to search for messages",
action="append")
parser.add_option("-m", dest='module',
help="write the module file",
action='store_true', default=False)
parser.add_option("-e", dest='emdir',
help="directory containing template files",
default=sys.path[0])
(options, argv) = parser.parse_args(argv)
if( not options.package or not options.outdir or not options.emdir):
parser.print_help()
exit(-1)
if( options.module ):
generate_module(options.package, options.outdir, options.emdir, module_template_dict)
else:
if len(argv) > 1:
generate_from_file(argv[1], options.package, options.outdir, options.emdir, options.includepath, msg_template_dict, srv_template_dict)
else:
parser.print_help()
exit(-1)

View File

View File

@ -0,0 +1,4 @@
# This contains the position of a point in free space
float64 x
float64 y
float64 z

View File

@ -0,0 +1,11 @@
# This contains the position of a point in free space(with 32 bits of precision).
# It is recommeded to use Point wherever possible instead of Point32.
#
# This recommendation is to promote interoperability.
#
# This message is designed to take up less space when sending
# lots of points at once, as in the case of a PointCloud.
float32 x
float32 y
float32 z

View File

@ -0,0 +1,3 @@
# This represents a Point with reference coordinate frame and timestamp
Header header
Point point

View File

@ -0,0 +1,2 @@
#A specification of a polygon where the first and last points are assumed to be connected
geometry_msgs/Point32[] points

View File

@ -0,0 +1,3 @@
# This represents a Polygon with reference coordinate frame and timestamp
Header header
Polygon polygon

View File

@ -0,0 +1,3 @@
# A representation of pose in free space, composed of position and orientation.
Point position
Quaternion orientation

View File

@ -0,0 +1,5 @@
# This expresses a position and orientation on a 2D manifold.
float64 x
float64 y
float64 theta

View File

@ -0,0 +1,5 @@
# An array of poses with a header for global reference.
Header header
geometry_msgs/Pose[] poses

View File

@ -0,0 +1,3 @@
# A Pose with reference coordinate frame and timestamp
Header header
Pose pose

View File

@ -0,0 +1,9 @@
# This represents a pose in free space with uncertainty.
Pose pose
# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance

View File

@ -0,0 +1,4 @@
# This expresses an estimated pose with a reference coordinate frame and timestamp
Header header
PoseWithCovariance pose

View File

@ -0,0 +1,6 @@
# This represents an orientation in free space in quaternion form.
float64 x
float64 y
float64 z
float64 w

View File

@ -0,0 +1,4 @@
# This represents an orientation with reference coordinate frame and timestamp.
Header header
Quaternion quaternion

View File

@ -0,0 +1,4 @@
# This represents the transform between two coordinate frames in free space.
Vector3 translation
Quaternion rotation

View File

@ -0,0 +1,10 @@
# This expresses a transform from coordinate frame header.frame_id
# to the coordinate frame child_frame_id
#
# This message is mostly used by the
# <a href="http://www.ros.org/wiki/tf">tf</a> package.
# See it's documentation for more information.
Header header
string child_frame_id # the frame id of the child frame
Transform transform

View File

@ -0,0 +1,3 @@
# This expresses velocity in free space broken into it's linear and angular parts.
Vector3 linear
Vector3 angular

View File

@ -0,0 +1,3 @@
# A twist with reference coordinate frame and timestamp
Header header
Twist twist

View File

@ -0,0 +1,9 @@
# This expresses velocity in free space with uncertianty.
Twist twist
# Row-major representation of the 6x6 covariance matrix
# The orientation parameters use a fixed-axis representation.
# In order, the parameters are:
# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
float64[36] covariance

View File

@ -0,0 +1,3 @@
# This represents an estimate twist with reference coordinate frame and timestamp.
Header header
TwistWithCovariance twist

View File

@ -0,0 +1,5 @@
# This represents a vector in free space.
float64 x
float64 y
float64 z

View File

@ -0,0 +1,3 @@
# This represents a Vector3 with reference coordinate frame and timestamp
Header header
Vector3 vector

View File

@ -0,0 +1,4 @@
# This represents force in free space, separated into
# it's linear and angular parts.
Vector3 force
Vector3 torque

View File

@ -0,0 +1,3 @@
# A wrench with reference coordinate frame and timestamp
Header header
Wrench wrench

View File

@ -0,0 +1 @@
std_msgs/NonExistent data

View File

@ -0,0 +1 @@
NonExistent data

View File

@ -0,0 +1,4 @@
# roslib/Clock is used for publishing simulated time in ROS.
# This message simply communicates the current time.
# For more information, see http://www.ros.org/wiki/Clock
time clock

View File

@ -0,0 +1,19 @@
##
## Severity level constants
##
byte DEBUG=1 #debug level
byte INFO=2 #general level
byte WARN=4 #warning level
byte ERROR=8 #error level
byte FATAL=16 #fatal/critical level
##
## Fields
##
Header header
byte level
string name # name of the node
string msg # message
string file # file the message came from
string function # function the message came from
uint32 line # line the message came from
string[] topics # topic names that the node publishes

View File

@ -0,0 +1,131 @@
# This message defines meta information for a camera. It should be in a
# camera namespace on topic "camera_info" and accompanied by up to five
# image topics named:
#
# image_raw - raw data from the camera driver, possibly Bayer encoded
# image - monochrome, distorted
# image_color - color, distorted
# image_rect - monochrome, rectified
# image_rect_color - color, rectified
#
# The image_pipeline contains packages (image_proc, stereo_image_proc)
# for producing the four processed image topics from image_raw and
# camera_info. The meaning of the camera parameters are described in
# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
#
# The image_geometry package provides a user-friendly interface to
# common operations using this meta information. If you want to, e.g.,
# project a 3d point into image coordinates, we strongly recommend
# using image_geometry.
#
# If the camera is uncalibrated, the matrices D, K, R, P should be left
# zeroed out. In particular, clients may assume that K[0] == 0.0
# indicates an uncalibrated camera.
#######################################################################
# Image acquisition info #
#######################################################################
# Time of image acquisition, camera coordinate frame ID
Header header # Header timestamp should be acquisition time of image
# Header frame_id should be optical frame of camera
# origin of frame should be optical center of camera
# +x should point to the right in the image
# +y should point down in the image
# +z should point into the plane of the image
#######################################################################
# Calibration Parameters #
#######################################################################
# These are fixed during camera calibration. Their values will be the #
# same in all messages until the camera is recalibrated. Note that #
# self-calibrating systems may "recalibrate" frequently. #
# #
# The internal parameters can be used to warp a raw (distorted) image #
# to: #
# 1. An undistorted image (requires D and K) #
# 2. A rectified image (requires D, K, R) #
# The projection matrix P projects 3D points into the rectified image.#
#######################################################################
# The image dimensions with which the camera was calibrated. Normally
# this will be the full camera resolution in pixels.
uint32 height
uint32 width
# The distortion model used. Supported models are listed in
# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
# simple model of radial and tangential distortion - is sufficient.
string distortion_model
# The distortion parameters, size depending on the distortion model.
# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
float64[] D
# Intrinsic camera matrix for the raw (distorted) images.
# [fx 0 cx]
# K = [ 0 fy cy]
# [ 0 0 1]
# Projects 3D points in the camera coordinate frame to 2D pixel
# coordinates using the focal lengths (fx, fy) and principal point
# (cx, cy).
float64[9] K # 3x3 row-major matrix
# Rectification matrix (stereo cameras only)
# A rotation matrix aligning the camera coordinate system to the ideal
# stereo image plane so that epipolar lines in both stereo images are
# parallel.
float64[9] R # 3x3 row-major matrix
# Projection/camera matrix
# [fx' 0 cx' Tx]
# P = [ 0 fy' cy' Ty]
# [ 0 0 1 0]
# By convention, this matrix specifies the intrinsic (camera) matrix
# of the processed (rectified) image. That is, the left 3x3 portion
# is the normal camera intrinsic matrix for the rectified image.
# It projects 3D points in the camera coordinate frame to 2D pixel
# coordinates using the focal lengths (fx', fy') and principal point
# (cx', cy') - these may differ from the values in K.
# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
# also have R = the identity and P[1:3,1:3] = K.
# For a stereo pair, the fourth column [Tx Ty 0]' is related to the
# position of the optical center of the second camera in the first
# camera's frame. We assume Tz = 0 so both cameras are in the same
# stereo image plane. The first camera always has Tx = Ty = 0. For
# the right (second) camera of a horizontal stereo pair, Ty = 0 and
# Tx = -fx' * B, where B is the baseline between the cameras.
# Given a 3D point [X Y Z]', the projection (x, y) of the point onto
# the rectified image is given by:
# [u v w]' = P * [X Y Z 1]'
# x = u / w
# y = v / w
# This holds for both images of a stereo pair.
float64[12] P # 3x4 row-major matrix
#######################################################################
# Operational Parameters #
#######################################################################
# These define the image region actually captured by the camera #
# driver. Although they affect the geometry of the output image, they #
# may be changed freely without recalibrating the camera. #
#######################################################################
# Binning refers here to any camera setting which combines rectangular
# neighborhoods of pixels into larger "super-pixels." It reduces the
# resolution of the output image to
# (width / binning_x) x (height / binning_y).
# The default values binning_x = binning_y = 0 is considered the same
# as binning_x = binning_y = 1 (no subsampling).
uint32 binning_x
uint32 binning_y
# Region of interest (subwindow of full camera resolution), given in
# full resolution (unbinned) image coordinates. A particular ROI
# always denotes the same window of pixels on the camera sensor,
# regardless of binning settings.
# The default setting of roi (all values 0) is considered the same as
# full resolution (roi.width = width, roi.height = height).
RegionOfInterest roi

View File

@ -0,0 +1,24 @@
# This message is used by the PointCloud message to hold optional data
# associated with each point in the cloud. The length of the values
# array should be the same as the length of the points array in the
# PointCloud, and each value should be associated with the corresponding
# point.
# Channel names in existing practice include:
# "u", "v" - row and column (respectively) in the left stereo image.
# This is opposite to usual conventions but remains for
# historical reasons. The newer PointCloud2 message has no
# such problem.
# "rgb" - For point clouds produced by color stereo cameras. uint8
# (R,G,B) values packed into the least significant 24 bits,
# in order.
# "intensity" - laser or pixel intensity.
# "distance"
# The channel name should give semantics of the channel (e.g.
# "intensity" instead of "value").
string name
# The values array should be 1-1 with the elements of the associated
# PointCloud.
float32[] values

View File

@ -0,0 +1,13 @@
# This message contains a compressed image
Header header # Header timestamp should be acquisition time of image
# Header frame_id should be optical frame of camera
# origin of frame should be optical center of cameara
# +x should point to the right in the image
# +y should point down in the image
# +z should point into to plane of the image
string format # Specifies the format of the data
# Acceptable values:
# jpeg, png
uint8[] data # Compressed image buffer

View File

@ -0,0 +1,27 @@
# This message contains an uncompressed image
# (0, 0) is at top-left corner of image
#
Header header # Header timestamp should be acquisition time of image
# Header frame_id should be optical frame of camera
# origin of frame should be optical center of cameara
# +x should point to the right in the image
# +y should point down in the image
# +z should point into to plane of the image
# If the frame_id here and the frame_id of the CameraInfo
# message associated with the image conflict
# the behavior is undefined
uint32 height # image height, that is, number of rows
uint32 width # image width, that is, number of columns
# The legal values for encoding are in file src/image_encodings.cpp
# If you want to standardize a new string format, join
# ros-users@lists.sourceforge.net and send an email proposing a new encoding.
string encoding # Encoding of pixels -- channel meaning, ordering, size
# taken from the list of strings in src/image_encodings.cpp
uint8 is_bigendian # is this data bigendian?
uint32 step # Full row length in bytes
uint8[] data # actual matrix data, size is (step * rows)

View File

@ -0,0 +1,20 @@
# This is a message to hold data from an IMU (Inertial Measurement Unit)
#
# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec
#
# If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the datasheet, just put those along the diagonal)
# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the data a covariance will have to be assumed or gotten from some other source
#
# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation estimate), please set element 0 of the associated covariance matrix to -1
# If you are interpreting this message, please check for a value of -1 in the first element of each covariance matrix, and disregard the associated estimate.
Header header
geometry_msgs/Quaternion orientation
float64[9] orientation_covariance # Row major about x, y, z axes
geometry_msgs/Vector3 angular_velocity
float64[9] angular_velocity_covariance # Row major about x, y, z axes
geometry_msgs/Vector3 linear_acceleration
float64[9] linear_acceleration_covariance # Row major x, y z

Some files were not shown because too many files have changed in this diff Show More