RobotML / RobotML-SDK

RobotML-SDK is an implementation of the Robot Modeling language. It is based upon Papyrus modeling tool (http://www.papyrus.org) which is itself based upon Eclipse framework (http://www.eclipse.org).
2 stars 1 forks source link

Morse : No generation for sensors and actuators #113

Open Farges opened 11 years ago

Farges commented 11 years ago

As shown on the figure, the AirOARP model includes: Capture du 2013-04-10 14:59:48 A camera, a gyroscope, a GPS and a destination. Those types are standard in Morse. The objects are linked to the RMax in an architecture diagram: Capture du 2013-04-10 15:00:54 However, no code is generated for those objects in the python file: https://github.com/RobotML/RobotML-SDK/blob/master/tests/models/AirOARP/morse-generated-files/morseTalc.py Expected generation is:

CameraMain_002 = Sensor('video_camera')
CameraMain_002.translate(x=0.6, z=0.38)
CameraMain_002.rotate(x=-1.5708)
mRMax.append(CameraMain_002)
CameraMain_002.properties(capturing = True,
                          cam_width = 128,
                          cam_height = 128,
                          cam_focal = 35.0000)

Gyroscope_001 = Sensor('gyroscope')
Gyroscope_001.translate(x=0.4, z=0.82)
mRMax.append(Gyroscope_001)
Motion_Controller = Actuator('destination')
mRMax.append(Motion_Controller)
GPS_001.configure_mw('ros')
CameraMain_002.configure_mw('ros')
Motion_Controller.configure_mw('ros')
Gyroscope_001.configure_mw('ros')
SergeStinckwich commented 11 years ago

If we want to generate MORSE 1.0 new API, we have to generate the following file:

CameraMain_002 = VideoCamera()
CameraMain_002.translate(x=0.6, z=0.38)
CameraMain_002.rotate(x=-1.5708)
mRMax.append(CameraMain_002)
CameraMain_002.properties(capturing = True,
                          cam_width = 128,
                          cam_height = 128,
                          cam_focal = 35.0000)

Gyroscope_001 = Gyroscope()
Gyroscope_001.translate(x=0.4, z=0.82)
mRMax.append(Gyroscope_001)
Motion_Controller = Destination()
mRMax.append(Motion_Controller)
GPS_001.configure_mw('ros')
CameraMain_002.configure_mw('ros')
Motion_Controller.configure_mw('ros')
Gyroscope_001.configure_mw('ros')
Farges commented 11 years ago

More precisely the expected generation in 1.0 is :

from morse.builder import *
mRMax = RMax()
mRMax.name = "RMAX"
GPS_001 = GPS()
mRMax.append(GPS_001)
CameraMain_002 = VideoCamera()
CameraMain_002.translate(x=0.6, z=0.38)
CameraMain_002.rotate(x=-1.5708)
mRMax.append(CameraMain_002)
CameraMain_002.properties(capturing = True,
                          cam_width = 128,
                          cam_height = 128,
                          cam_focal = 35.0000)
Gyroscope_001 = Gyroscope()
Gyroscope_001.translate(x=0.4, z=0.82)
mRMax.append(Gyroscope_001)
Motion_Controller = Destination()
mRMax.append(Motion_Controller)
mRMax.translate(x=5.0, y=0.0, z=9.0)
GPS_001.add_stream('ros')
CameraMain_002.add_stream('ros')
Motion_Controller.add_stream('ros')
Gyroscope_001.add_stream('ros')
env = Environment('land-1/trees')
env.aim_camera([1.0470, 0, 0.7854])
env.place_camera([10, -10, 15])

Note that configure_mv do not exist in 1.0.; add_stream should be used instead.