Skip to content

Commit 7ea4fd1

Browse files
author
Kareem Shehata
committed
Merged applanix_msgs with applanix_srvs and adapted the mapping.py
script to generate all of the required elements. Updated the CMakeLists.txt for applanix_msgs to generate services and AllMsgs. Updated applanix_bridge for the changes.
1 parent 5eff203 commit 7ea4fd1

File tree

13 files changed

+154
-236
lines changed

13 files changed

+154
-236
lines changed

.gitignore

+2-2
Original file line numberDiff line numberDiff line change
@@ -5,5 +5,5 @@
55
msg_gen
66
srv_gen
77
build
8-
applanix_srvs/srv/*
9-
applanix_srvs/msg/*
8+
applanix_msgs/srv/*
9+
applanix_msgs/msg/AllMsgs.msg

applanix_bridge/src/applanix_bridge/control.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444
import rospy
4545

4646
# ROS messages and services
47-
import applanix_srvs.srv
47+
import applanix_msgs.srv
4848
import applanix_msgs.msg
4949

5050
# Node
@@ -75,7 +75,7 @@ def run(self):
7575

7676
# Send the navigation mode every n seconds so that the Applanix device
7777
# doesn't close the connection on us.
78-
set_nav_mode = rospy.ServiceProxy("nav_mode", applanix_srvs.srv.NavModeControl)
78+
set_nav_mode = rospy.ServiceProxy("nav_mode", applanix_msgs.srv.SetNavModeControl)
7979
nav_mode_msg = applanix_msgs.msg.NavModeControl(mode=applanix_msgs.msg.NavModeControl.MODE_NAVIGATE)
8080
while not self.finish.is_set():
8181
rospy.sleep(SILENCE_INTERVAL)
@@ -90,7 +90,7 @@ class ServiceHandler(object):
9090
def __init__(self, msg_num, port):
9191
self.name, data_class = mapping.msgs[msg_num]
9292
self.port = port
93-
self.service = rospy.Service(self.name, getattr(applanix_srvs.srv, data_class.__name__), self.handle)
93+
self.service = rospy.Service(self.name, getattr(applanix_msgs.srv, "Set" + data_class.__name__), self.handle)
9494

9595
# Part of the outbound message to Applanix device.
9696
self.header = applanix_msgs.msg.CommonHeader(start=applanix_msgs.msg.CommonHeader.START_MESSAGE, id=msg_num, length=0)

applanix_bridge/src/applanix_bridge/data.py

+1-2
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,6 @@
4545

4646
# ROS messages
4747
import applanix_msgs.msg
48-
import applanix_srvs.msg
4948

5049
# Node source
5150
from port import Port
@@ -65,7 +64,7 @@ def run(self):
6564
self.sock.settimeout(1.0)
6665

6766
# Aggregate message for republishing the sensor config as a single blob.
68-
all_msgs = applanix_srvs.msg.AllMsgs()
67+
all_msgs = applanix_msgs.msg.AllMsgs()
6968
all_msgs_pub = rospy.Publisher("config", all_msgs.__class__, latch=True)
7069

7170
# Listener object which tracks what topics have been subscribed to.

applanix_bridge/src/applanix_bridge/params.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444
import rospy
4545
import roslib.message
4646
import applanix_msgs.msg
47-
import applanix_srvs.srv
47+
import applanix_msgs.srv
4848

4949
response_codes = dict([(val, name) for name, val in applanix_msgs.msg.Ack.__dict__.items() if name.startswith("RESPONSE_")])
5050

@@ -111,7 +111,7 @@ def main():
111111

112112

113113
def call_applanix_service(name, req):
114-
service_defn = getattr(applanix_srvs.srv, req.__class__.__name__)
114+
service_defn = getattr(applanix_msgs.srv, "Set" + req.__class__.__name__)
115115
rospy.wait_for_service(name)
116116
ack = rospy.ServiceProxy(name, service_defn)(req).ack
117117
if ack.response_code != applanix_msgs.msg.Ack.RESPONSE_ACCEPTED:

applanix_bridge/test/basic_data_smoke.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@
4343
import rospy
4444

4545
from applanix_msgs.msg import NavigationSolution
46-
from applanix_srvs.msg import AllMsgs
46+
from applanix_msgs.msg import AllMsgs
4747
from diagnostic_msgs.msg import DiagnosticArray
4848
from sensor_msgs.msg import NavSatFix, Imu
4949

applanix_msgs/CMakeLists.txt

+43
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,46 @@ find_package(catkin REQUIRED COMPONENTS
1111
# the message mappings to Applanix.
1212
catkin_python_setup()
1313

14+
SET(mapping_py "${CMAKE_CURRENT_SOURCE_DIR}/src/applanix_msgs/mapping.py")
15+
16+
# get the list of all of the messages for which to generate services
17+
execute_process(COMMAND ${mapping_py} OUTPUT_VARIABLE gen_msg_names
18+
OUTPUT_STRIP_TRAILING_WHITESPACE)
19+
20+
MESSAGE("Generating AllMsgs.msg")
21+
SET(all_msgs_path "${CMAKE_CURRENT_SOURCE_DIR}/msg/AllMsgs.msg")
22+
# need to do this if the file doesn't exist already
23+
execute_process(COMMAND ${mapping_py} -a OUTPUT_FILE ${all_msgs_path})
24+
25+
# custom command to generate AllMsgs
26+
add_custom_command(
27+
OUTPUT ${all_msgs_path} COMMAND ${mapping_py} -a > ${all_msgs_path}
28+
DEPENDS ${mapping_py}
29+
)
30+
31+
add_custom_target(AllMsgs.msg DEPENDS ${mapping_py})
32+
33+
# go through each of the message names and generate a service
34+
FOREACH(msg_name ${gen_msg_names})
35+
MESSAGE("Generating service definition for ${msg_name}")
36+
SET(srv_path "${CMAKE_CURRENT_SOURCE_DIR}/srv/Set${msg_name}.srv")
37+
execute_process(COMMAND ${mapping_py} -g ${msg_name} OUTPUT_FILE ${srv_path})
38+
SET(generated_srvs ${generated_srvs} "Set${msg_name}.srv;")
39+
40+
add_custom_command(
41+
OUTPUT ${srv_path}
42+
COMMAND ${mapping_py} -g ${msg_name} > ${srv_path}
43+
DEPENDS ${mapping_py}
44+
)
45+
46+
add_custom_target("Set${msg_name}.srv" DEPENDS ${mapping_py})
47+
48+
ENDFOREACH(msg_name)
49+
1450
## Generate messages in the 'msg' folder
1551
add_message_files(
1652
FILES
53+
AllMsgs.msg
1754
Ack.msg
1855
AidingSensorIntegrationControl.msg
1956
AidingSensorParams.msg
@@ -72,6 +109,12 @@ add_message_files(
72109
Version.msg
73110
)
74111

112+
## Service definitions generated above
113+
add_service_files(
114+
FILES
115+
${generated_srvs}
116+
)
117+
75118
generate_messages(
76119
DEPENDENCIES
77120
geometry_msgs

applanix_msgs/src/applanix_msgs/mapping.py

+102-81
Original file line numberDiff line numberDiff line change
@@ -39,95 +39,116 @@
3939
#
4040
# Please send comments, questions, or patches to skynet@clearpathrobotics.com
4141
#
42-
from applanix_msgs.msg import *
43-
4442

4543
# applanix group number : ( topic name, ROS message class, [opts] )
4644
groups = {
47-
1: ("nav", NavigationSolution),
48-
2: ("status/perf", NavigationPerformance),
49-
3: ("status/gnss/primary", GNSSStatus),
50-
4: ("imu", IMUData),
51-
5: ("events/1", Event),
52-
6: ("events/2", Event),
53-
7: ("status/pps", PPSStatus),
54-
8: ("status/logging", LoggingStatus),
55-
9: ("gams", GAMS),
56-
10: ("status/general", GeneralStatus),
57-
11: ("status/gnss/secondary", GNSSStatus),
58-
12: ("status/gnss/aux_1", GNSSAuxStatus),
59-
13: ("status/gnss/aux_2", GNSSAuxStatus),
60-
14: ("status/installation", CalibratedInstallationParameters),
61-
15: ("dmi", DMIData),
62-
17: ("status/user_time", UserTimeStatus),
63-
20: ("status/iin", IINSolutionStatus),
64-
21: ("status/base_gnss/1/modem", BaseGNSSModemStatus),
65-
22: ("status/base_gnss/2/modem", BaseGNSSModemStatus),
66-
23: ("raw/gnss/aux_1_display", RawData),
67-
24: ("raw/gnss/aux_2_display", RawData),
68-
25: ("status/dgps", GNSSDGPSStatus),
69-
26: ("status/dgps_stations", GNSSDGPSStationDatabase),
70-
30: ("events/3", Event),
71-
31: ("events/4", Event),
72-
32: ("events/5", Event),
73-
33: ("events/6", Event),
74-
99: ("status/version", Version),
75-
10001: ("raw/gnss/primary", RawData),
76-
10002: ("raw/imu", RawData),
77-
10003: ("raw/pps", RawPPS),
78-
10004: ("events/1", Event),
79-
10005: ("events/2", Event),
80-
10006: ("raw/dmi", RawDMI),
81-
10007: ("raw/gnss/aux_1", RawData),
82-
10008: ("raw/gnss/aux_2", RawData),
83-
10009: ("raw/gnss/secondary", RawData),
84-
10011: ("raw/base_gnss/1", RawData),
85-
10012: ("raw/base_gnss/2", RawData),
45+
1: ("nav", "NavigationSolution"),
46+
2: ("status/perf", "NavigationPerformance"),
47+
3: ("status/gnss/primary", "GNSSStatus"),
48+
4: ("imu", "IMUData"),
49+
5: ("events/1", "Event"),
50+
6: ("events/2", "Event"),
51+
7: ("status/pps", "PPSStatus"),
52+
8: ("status/logging", "LoggingStatus"),
53+
9: ("gams", "GAMS"),
54+
10: ("status/general", "GeneralStatus"),
55+
11: ("status/gnss/secondary", "GNSSStatus"),
56+
12: ("status/gnss/aux_1", "GNSSAuxStatus"),
57+
13: ("status/gnss/aux_2", "GNSSAuxStatus"),
58+
14: ("status/installation", "CalibratedInstallationParameters"),
59+
15: ("dmi", "DMIData"),
60+
17: ("status/user_time", "UserTimeStatus"),
61+
20: ("status/iin", "IINSolutionStatus"),
62+
21: ("status/base_gnss/1/modem", "BaseGNSSModemStatus"),
63+
22: ("status/base_gnss/2/modem", "BaseGNSSModemStatus"),
64+
23: ("raw/gnss/aux_1_display", "RawData"),
65+
24: ("raw/gnss/aux_2_display", "RawData"),
66+
25: ("status/dgps", "GNSSDGPSStatus"),
67+
26: ("status/dgps_stations", "GNSSDGPSStationDatabase"),
68+
30: ("events/3", "Event"),
69+
31: ("events/4", "Event"),
70+
32: ("events/5", "Event"),
71+
33: ("events/6", "Event"),
72+
99: ("status/version", "Version"),
73+
10001: ("raw/gnss/primary", "RawData"),
74+
10002: ("raw/imu", "RawData"),
75+
10003: ("raw/pps", "RawPPS"),
76+
10004: ("events/1", "Event"),
77+
10005: ("events/2", "Event"),
78+
10006: ("raw/dmi", "RawDMI"),
79+
10007: ("raw/gnss/aux_1", "RawData"),
80+
10008: ("raw/gnss/aux_2", "RawData"),
81+
10009: ("raw/gnss/secondary", "RawData"),
82+
10011: ("raw/base_gnss/1", "RawData"),
83+
10012: ("raw/base_gnss/2", "RawData"),
8684
}
8785

8886
msgs = {
89-
0: ("ack", Ack),
90-
20: ("general", GeneralParams),
91-
21: ("gams", GAMSParams),
92-
22: ("aiding_sensors", AidingSensorParams),
93-
24: ("user_accuracy", UserAccuracySpecs),
94-
30: ("primary_gnss_setup", GNSSSetup),
95-
31: ("secondary_gnss_setup", GNSSSetup),
96-
32: ("ip_address", IPAddress),
97-
33: ("event_setup", EventSetup),
98-
34: ("com_port_setup", COMPortSetup),
99-
35: ("nmea_message_select", NMEAMessageSelect),
100-
36: ("binary_message_select", BinaryMessageSelect),
101-
37: ("base_gnss_1_setup", BaseGNSSSetup),
102-
38: ("base_gnss_2_setup", BaseGNSSSetup),
103-
40: ("precise_gravity", PreciseGravitySpecs),
104-
41: ("primary_dgps_source", DGPSSourceControl),
105-
50: ("nav_mode", NavModeControl),
106-
51: ("display_port", PortControl),
107-
52: ("primary_data_port", PortControl),
108-
53: ("logging_port", LoggingControl),
109-
54: ("save_restore", SaveRestoreControl),
110-
55: ("time_sync", TimeSyncControl),
111-
57: ("installation_calibration", InstallationCalibrationControl),
112-
58: ("gams_calibration", GAMSCalibrationControl),
113-
61: ("secondary_data_port", PortControl),
114-
90: ("program", ProgramControl),
115-
91: ("gnss", GNSSControl),
116-
92: ("integration_diagnostics", IntegrationDiagnosticsControl),
117-
93: ("aiding_sensor_integration", AidingSensorIntegrationControl),
87+
0: ("ack", "Ack", False),
88+
20: ("general", "GeneralParams", True),
89+
21: ("gams", "GAMSParams", True),
90+
22: ("aiding_sensors", "AidingSensorParams", True),
91+
24: ("user_accuracy", "UserAccuracySpecs", True),
92+
30: ("primary_gnss_setup", "GNSSSetup", True),
93+
31: ("secondary_gnss_setup", "GNSSSetup", True),
94+
32: ("ip_address", "IPAddress", True),
95+
33: ("event_setup", "EventSetup", True),
96+
34: ("com_port_setup", "COMPortSetup", True),
97+
35: ("nmea_message_select", "NMEAMessageSelect", True),
98+
36: ("binary_message_select", "BinaryMessageSelect", True),
99+
37: ("base_gnss_1_setup", "BaseGNSSSetup", True),
100+
38: ("base_gnss_2_setup", "BaseGNSSSetup", True),
101+
40: ("precise_gravity", "PreciseGravitySpecs", True),
102+
41: ("primary_dgps_source", "DGPSSourceControl", True),
103+
50: ("nav_mode", "NavModeControl", True),
104+
51: ("display_port", "PortControl", True),
105+
52: ("primary_data_port", "PortControl", True),
106+
53: ("logging_port", "LoggingControl", True),
107+
54: ("save_restore", "SaveRestoreControl", False),
108+
55: ("time_sync", "TimeSyncControl", True),
109+
57: ("installation_calibration", "InstallationCalibrationControl", False),
110+
58: ("gams_calibration", "GAMSCalibrationControl", False),
111+
61: ("secondary_data_port", "PortControl", True),
112+
90: ("program", "ProgramControl", False),
113+
91: ("gnss", "GNSSControl", False),
114+
92: ("integration_diagnostics", "IntegrationDiagnosticsControl", True),
115+
93: ("aiding_sensor_integration", "AidingSensorIntegrationControl", True),
118116
}
119117

118+
if __name__ == '__main__':
119+
import sys
120+
# by default, print out all of the messages that correspond to services
121+
if len(sys.argv) <= 1 or sys.argv[1] == "-s":
122+
srvs = []
123+
for name, msg, in_all_msgs in msgs.values():
124+
if name != "ack" and msg not in srvs:
125+
srvs += [msg]
120126

121-
# Message excluded from the generated AllMsgs aggregate message.
122-
all_msgs_exclude = set([Ack, SaveRestoreControl, InstallationCalibrationControl,
123-
GAMSCalibrationControl, ProgramControl, GNSSControl])
124-
for name, msg in msgs.values():
125-
if msg in all_msgs_exclude:
126-
msg.in_all_msgs = False
127-
else:
128-
msg.in_all_msgs = True
127+
print ";".join(srvs)
129128

129+
elif sys.argv[1] == "-a":
130+
print "time last_changed"
131+
print "time last_sent"
132+
for name, msg, in_all_msgs in msgs.values():
133+
if in_all_msgs:
134+
print "applanix_msgs/%s %s" % (msg, name)
130135

131-
if __name__ == '__main__':
132-
from pprint import pprint
133-
pprint((groups, msgs))
136+
elif sys.argv[1] == "-g":
137+
msg_name = sys.argv[2]
138+
print "applanix_msgs/" + msg_name + " request"
139+
print "---"
140+
print "applanix_msgs/Ack ack"
141+
142+
143+
else:
144+
# magic to replace class names with actual class instances
145+
import applanix_msgs.msg
146+
for k in groups.keys():
147+
name, msg_name = groups[k]
148+
groups[k] = (name, applanix_msgs.msg.__dict__[msg_name])
149+
150+
for k in msgs.keys():
151+
name, msg_name, in_all_msgs = msgs[k]
152+
msgs[k] = (name, applanix_msgs.msg.__dict__[msg_name])
153+
msgs[k][1].in_all_msgs = in_all_msgs
154+
File renamed without changes.

applanix_srvs/CHANGELOG.rst

-22
This file was deleted.

applanix_srvs/CMakeLists.txt

-30
This file was deleted.

0 commit comments

Comments
 (0)