diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros index 10e03ad..e69de29 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros @@ -1,8 +0,0 @@ -PackageSet { - CatkinPackage joy { - Artifact joy_node { Node { name joy_node - Publishers { - Publisher { name "joy" message "sensor_msgs.Joy" }, - Publisher { name "diagnostics" message "diagnostic_msgs.DiagnosticArray" } - }} -}}} \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros1 b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros1 new file mode 100644 index 0000000..ffe2f8e --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros1 @@ -0,0 +1,9 @@ +joy: + artifacts: + joy_node: + node: joy_node + publishers: + joy: + type: "sensor_msgs.Joy" + diagnostics: + type: "diagnostic_msgs.DiagnosticArray" \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Laser2DScan.ros b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Laser2DScan.ros deleted file mode 100644 index 767340b..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Laser2DScan.ros +++ /dev/null @@ -1,9 +0,0 @@ -PackageSet { - CatkinPackage scan_2d { - Artifact scan_2d { Node { name scan_2d - Publishers { - Publisher { name scan message "sensor_msgs.LaserScan" } , - Publisher { name diagnostics message "diagnostic_msgs.DiagnosticArray" - }}}} - -}} \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Laser2DScan.ros1 b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Laser2DScan.ros1 new file mode 100644 index 0000000..199f60d --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Laser2DScan.ros1 @@ -0,0 +1,9 @@ +scan_2d: + artifacts: + scan_2d: + node: scan_2d + publishers: + scan: + type: "sensor_msgs.LaserScan" + diagnostics: + type: "diagnostic_msgs.DiagnosticArray" \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Teleop.ros b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Teleop.ros deleted file mode 100644 index 630c1c8..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Teleop.ros +++ /dev/null @@ -1,8 +0,0 @@ -PackageSet { - CatkinPackage teleop { - Artifact joystick_teleop_node { - Node { name joystick_teleop_node - Publishers { Publisher { name cmd_vel message "geometry_msgs.Twist" } } - Subscribers { Subscriber { name joy message "sensor_msgs.Joy" } } - } -}}} \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Teleop.ros1 b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Teleop.ros1 new file mode 100644 index 0000000..6f7f407 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Teleop.ros1 @@ -0,0 +1,10 @@ +teleop: + artifacts: + joystick_teleop_node: + node: joystick_teleop_node + publishers: + cmd_vel: + type: "geometry_msgs.Twist" + subscribers: + joy: + type:"sensor_msgs.Joy" \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/common_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/common_msgs.ros index 69ebe6e..7e975e6 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/common_msgs.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/common_msgs.ros @@ -1,119 +1,337 @@ -PackageSet{ - Package geometry_msgs{ Specs { - TopicSpec Accel{ message { Vector3 linear Vector3 angular }}, - TopicSpec AccelStamped{ message { Header header Accel accel }}, - TopicSpec AccelWithCovariance{ message { Accel accel float64[] covariance }}, - TopicSpec AccelWithCovarianceStamped{ message { Header header AccelWithCovariance accel }}, - TopicSpec Inertia{ message { float64 m "geometry_msgs.Vector3" com float64 ixx float64 ixy float64 ixz float64 iyy float64 iyz float64 izz }}, - TopicSpec InertiaStamped{ message { Header header Inertia inertia }}, - TopicSpec Point{ message { float64 x float64 y float64 z }}, - TopicSpec Point32{ message { float32 x float32 y float32 z }}, - TopicSpec PointStamped{ message { Header header Point point }}, - TopicSpec Polygon{ message { Point32[] points }}, - TopicSpec PolygonStamped{ message { Header header Polygon polygon }}, - TopicSpec Pose{ message { Point position Quaternion orientation }}, - TopicSpec Pose2D{ message { float64 x float64 y float64 theta }}, - TopicSpec PoseArray{ message { Header header Pose[] poses }}, - TopicSpec PoseStamped{ message { Header header Pose pose }}, - TopicSpec PoseWithCovariance{ message { Pose pose float64[] covariance }}, - TopicSpec PoseWithCovarianceStamped{ message { Header header PoseWithCovariance pose }}, - TopicSpec Quaternion{ message { float64 x float64 y float64 z float64 w }}, - TopicSpec QuaternionStamped{ message { Header header Quaternion quaternion }}, - TopicSpec Transform{ message { Vector3 translation Quaternion rotation }}, - TopicSpec TransformStamped{ message { Header header string child_frame_id Transform transform }}, - TopicSpec Twist{ message { Vector3 linear Vector3 angular }}, - TopicSpec TwistStamped{ message { Header header Twist twist }}, - TopicSpec TwistWithCovariance{ message { Twist twist float64[] covariance }}, - TopicSpec TwistWithCovarianceStamped{ message { Header header TwistWithCovariance twist }}, - TopicSpec Vector3{ message { float64 x float64 y float64 z }}, - TopicSpec Vector3Stamped{ message { Header header Vector3 vector }}, - TopicSpec Wrench{ message { Vector3 force Vector3 torque }}, - TopicSpec WrenchStamped{ message { Header header Wrench wrench }} - }}, - Package actionlib_msgs{ Specs { - TopicSpec GoalID{ message { time stamp string id }}, - TopicSpec GoalStatus{ message { GoalID goal_id uint8 status uint8 PENDING=0 uint8 ACTIVE=1 uint8 PREEMPTED=2 uint8 SUCCEEDED=3 uint8 ABORTED=4 uint8 REJECTED=5 uint8 PREEMPTING=6 uint8 RECALLING=7 uint8 RECALLED=8 uint8 LOST=9 string text }}, - TopicSpec GoalStatusArray{ message { Header header GoalStatus[] status_list }} - }}, - Package diagnostic_msgs{ Specs { - TopicSpec DiagnosticArray{ message { Header header DiagnosticStatus[] status }}, - TopicSpec DiagnosticStatus{ message { byte OK=0 byte WARN=1 byte ERROR=2 byte STALE=3 byte level string name string message string hardware_id KeyValue[] values }}, - TopicSpec KeyValue{ message { string key string value }}, - ServiceSpec AddDiagnostics{ request { string load_namespace } response { bool success string message } }, - ServiceSpec SelfTest{ request { } response { string id byte passed DiagnosticStatus[] status } } - }}, - Package nav_msgs{ Specs { - TopicSpec GetMapAction{ message { GetMapActionGoal action_goal GetMapActionResult action_result GetMapActionFeedback action_feedback }}, - TopicSpec GetMapActionFeedback{ message { Header header "actionlib_msgs.GoalStatus" status GetMapFeedback feedback }}, - TopicSpec GetMapActionGoal{ message { Header header "actionlib_msgs.GoalID" goal_id GetMapGoal goal }}, - TopicSpec GetMapActionResult{ message { Header header "actionlib_msgs.GoalStatus" status GetMapResult result }}, - TopicSpec GetMapFeedback{ message { }}, - TopicSpec GetMapGoal{ message { }}, - TopicSpec GetMapResult{ message { "nav_msgs.OccupancyGrid" map }}, - TopicSpec GridCells{ message { Header header float32 cell_width float32 cell_height "geometry_msgs.Point"[] cells }}, - TopicSpec MapMetaData{ message { time map_load_time float32 resolution uint32 width uint32 height "geometry_msgs.Pose" origin }}, - TopicSpec OccupancyGrid{ message { Header header MapMetaData info int8[] data }}, - TopicSpec Odometry{ message { Header header string child_frame_id "geometry_msgs.PoseWithCovariance" pose "geometry_msgs.TwistWithCovariance" twist }}, - TopicSpec Path{ message { Header header "geometry_msgs.PoseStamped"[] poses }}, - ServiceSpec GetMap{ request { } response { "nav_msgs.OccupancyGrid" map } }, - ServiceSpec GetPlan{ request { "geometry_msgs.PoseStamped" start "geometry_msgs.PoseStamped" goal float32 tolerance } response { "nav_msgs.Path" plan } }, - ServiceSpec SetMap{ request { "nav_msgs.OccupancyGrid" map "geometry_msgs.PoseWithCovarianceStamped" initial_pose } response { bool success } } - }}, - Package sensor_msgs{ Specs { - TopicSpec BatteryState{ message { uint8 POWER_SUPPLY_STATUS_UNKNOWN=0 uint8 POWER_SUPPLY_STATUS_CHARGING=1 uint8 POWER_SUPPLY_STATUS_DISCHARGING=2 uint8 POWER_SUPPLY_STATUS_NOT_CHARGING=3 uint8 POWER_SUPPLY_STATUS_FULL=4 uint8 POWER_SUPPLY_HEALTH_UNKNOWN=0 uint8 POWER_SUPPLY_HEALTH_GOOD=1 uint8 POWER_SUPPLY_HEALTH_OVERHEAT=2 uint8 POWER_SUPPLY_HEALTH_DEAD=3 uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE=4 uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE=5 uint8 POWER_SUPPLY_HEALTH_COLD=6 uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE=7 uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE=8 uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN=0 uint8 POWER_SUPPLY_TECHNOLOGY_NIMH=1 uint8 POWER_SUPPLY_TECHNOLOGY_LION=2 uint8 POWER_SUPPLY_TECHNOLOGY_LIPO=3 uint8 POWER_SUPPLY_TECHNOLOGY_LIFE=4 uint8 POWER_SUPPLY_TECHNOLOGY_NICD=5 uint8 POWER_SUPPLY_TECHNOLOGY_LIMN=6 Header header float32 voltage float32 current float32 charge float32 capacity float32 design_capacity float32 percentage uint8 power_supply_status uint8 power_supply_health uint8 power_supply_technology bool present float32[] cell_voltage string location string serial_number }}, - TopicSpec CameraInfo{ message { Header header uint32 height uint32 width string distortion_model float64[] D float64[] K float64[] R float64[] P uint32 binning_x uint32 binning_y RegionOfInterest roi }}, - TopicSpec ChannelFloat32{ message { string name float32[] values }}, - TopicSpec CompressedImage{ message { Header header string format uint8[] data }}, - TopicSpec FluidPressure{ message { Header header float64 fluid_pressure float64 variance }}, - TopicSpec Illuminance{ message { Header header float64 illuminance float64 variance }}, - TopicSpec Image{ message { Header header uint32 height uint32 width string encoding uint8 is_bigendian uint32 step uint8[] data }}, - TopicSpec Imu{ message { Header header "geometry_msgs.Quaternion" orientation float64[] orientation_covariance "geometry_msgs.Vector3" angular_velocity float64[] angular_velocity_covariance "geometry_msgs.Vector3" linear_acceleration float64[] linear_acceleration_covariance }}, - TopicSpec JointState{ message { Header header string[] name float64[] position float64[] velocity float64[] effort }}, - TopicSpec Joy{ message { Header header float32[] axes int32[] buttons }}, - TopicSpec JoyFeedback{ message { uint8 TYPE_LED=0 uint8 TYPE_RUMBLE=1 uint8 TYPE_BUZZER=2 uint8 type uint8 id float32 intensity }}, - TopicSpec JoyFeedbackArray{ message { JoyFeedback[] array }}, - TopicSpec LaserEcho{ message { float32[] echoes }}, - TopicSpec LaserScan{ message { Header header float32 angle_min float32 angle_max float32 angle_increment float32 time_increment float32 scan_time float32 range_min float32 range_max float32[] ranges float32[] intensities }}, - TopicSpec MagneticField{ message { Header header "geometry_msgs.Vector3" magnetic_field float64[] magnetic_field_covariance }}, - TopicSpec MultiDOFJointState{ message { Header header string[] joint_names "geometry_msgs.Transform"[] transforms "geometry_msgs.Twist"[] twist "geometry_msgs.Wrench"[] wrench }}, - TopicSpec MultiEchoLaserScan{ message { Header header float32 angle_min float32 angle_max float32 angle_increment float32 time_increment float32 scan_time float32 range_min float32 range_max LaserEcho[] ranges LaserEcho[] intensities }}, - TopicSpec NavSatFix{ message { Header header NavSatStatus status float64 latitude float64 longitude float64 altitude float64[] position_covariance uint8 COVARIANCE_TYPE_UNKNOWN=0 uint8 COVARIANCE_TYPE_APPROXIMATED=1 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2 uint8 COVARIANCE_TYPE_KNOWN=3 uint8 position_covariance_type }}, - TopicSpec NavSatStatus{ message { int8 STATUS_NO_FIX=-1 int8 STATUS_FIX=0 int8 STATUS_SBAS_FIX=1 int8 STATUS_GBAS_FIX=2 int8 status uint16 SERVICE_GPS=1 uint16 SERVICE_GLONASS=2 uint16 SERVICE_COMPASS=4 uint16 SERVICE_GALILEO=8 uint16 service }}, - TopicSpec PointCloud{ message { Header header "geometry_msgs.Point32"[] points ChannelFloat32[] channels }}, - TopicSpec PointCloud2{ message { Header header uint32 height uint32 width PointField[] fields bool is_bigendian uint32 point_step uint32 row_step uint8[] data bool is_dense }}, - TopicSpec PointField{ message { uint8 INT8=1 uint8 UINT8=2 uint8 INT16=3 uint8 UINT16=4 uint8 INT32=5 uint8 UINT32=6 uint8 FLOAT32=7 uint8 FLOAT64=8 string name uint32 offset uint8 datatype uint32 count }}, - TopicSpec Range{ message { Header header uint8 ULTRASOUND=0 uint8 INFRARED=1 uint8 radiation_type float32 field_of_view float32 min_range float32 max_range float32 range }}, - TopicSpec RegionOfInterest{ message { uint32 x_offset uint32 y_offset uint32 height uint32 width bool do_rectify }}, - TopicSpec RelativeHumidity{ message { Header header float64 relative_humidity float64 variance }}, - TopicSpec Temperature{ message { Header header float64 temperature float64 variance }}, - TopicSpec TimeReference{ message { Header header time time_ref string source }}, - ServiceSpec SetCameraInfo{ request { "sensor_msgs.CameraInfo" camera_info } response { bool success string status_message } } - }}, - Package shape_msgs{ Specs { - TopicSpec Mesh{ message { MeshTriangle[] triangles "geometry_msgs.Point"[] vertices }}, - TopicSpec MeshTriangle{ message { uint32[] vertex_indices }}, - TopicSpec Plane{ message { float64[] coef }}, - TopicSpec SolidPrimitive{ message { uint8 BOX=1 uint8 SPHERE=2 uint8 CYLINDER=3 uint8 CONE=4 uint8 type float64[] dimensions uint8 BOX_X=0 uint8 BOX_Y=1 uint8 BOX_Z=2 uint8 SPHERE_RADIUS=0 uint8 CYLINDER_HEIGHT=0 uint8 CYLINDER_RADIUS=1 uint8 CONE_HEIGHT=0 uint8 CONE_RADIUS=1 }} - }}, - Package stereo_msgs{ Specs { - TopicSpec DisparityImage{ message { Header header "sensor_msgs.Image" image float32 f float32 T "sensor_msgs.RegionOfInterest" valid_window float32 min_disparity float32 max_disparity float32 delta_d }} - }}, - Package trajectory_msgs{ Specs { - TopicSpec JointTrajectory{ message { Header header string[] joint_names JointTrajectoryPoint[] points }}, - TopicSpec JointTrajectoryPoint{ message { float64[] positions float64[] velocities float64[] accelerations float64[] effort duration time_from_start }}, - TopicSpec MultiDOFJointTrajectory{ message { Header header string[] joint_names MultiDOFJointTrajectoryPoint[] points }}, - TopicSpec MultiDOFJointTrajectoryPoint{ message { "geometry_msgs.Transform"[] transforms "geometry_msgs.Twist"[] velocities "geometry_msgs.Twist"[] accelerations duration time_from_start }} - }}, - Package visualization_msgs{ Specs { - TopicSpec ImageMarker{ message { uint8 CIRCLE=0 uint8 LINE_STRIP=1 uint8 LINE_LIST=2 uint8 POLYGON=3 uint8 POINTS=4 uint8 ADD=0 uint8 REMOVE=1 Header header string ns int32 id int32 type int32 action "geometry_msgs.Point" position float32 scale "std_msgs.ColorRGBA" outline_color uint8 filled "std_msgs.ColorRGBA" fill_color duration lifetime "geometry_msgs.Point"[] points "std_msgs.ColorRGBA"[] outline_colors }}, - TopicSpec InteractiveMarker{ message { Header header "geometry_msgs.Pose" pose string name string description float32 scale MenuEntry[] menu_entries InteractiveMarkerControl[] controls }}, - TopicSpec InteractiveMarkerControl{ message { string name "geometry_msgs.Quaternion" orientation uint8 INHERIT=0 uint8 FIXED=1 uint8 VIEW_FACING=2 uint8 orientation_mode uint8 NONE=0 uint8 MENU=1 uint8 BUTTON=2 uint8 MOVE_AXIS=3 uint8 MOVE_PLANE=4 uint8 ROTATE_AXIS=5 uint8 MOVE_ROTATE=6 uint8 MOVE_3D=7 uint8 ROTATE_3D=8 uint8 MOVE_ROTATE_3D=9 uint8 interaction_mode bool always_visible Marker[] markers bool independent_marker_orientation string description }}, - TopicSpec InteractiveMarkerFeedback{ message { Header header string client_id string marker_name string control_name uint8 KEEP_ALIVE=0 uint8 POSE_UPDATE=1 uint8 MENU_SELECT=2 uint8 BUTTON_CLICK=3 uint8 MOUSE_DOWN=4 uint8 MOUSE_UP=5 uint8 event_type "geometry_msgs.Pose" pose uint32 menu_entry_id "geometry_msgs.Point" mouse_point bool mouse_point_valid }}, - TopicSpec InteractiveMarkerInit{ message { string server_id uint64 seq_num InteractiveMarker[] markers }}, - TopicSpec InteractiveMarkerPose{ message { Header header "geometry_msgs.Pose" pose string name }}, - TopicSpec InteractiveMarkerUpdate{ message { string server_id uint64 seq_num uint8 KEEP_ALIVE=0 uint8 UPDATE=1 uint8 type InteractiveMarker[] markers InteractiveMarkerPose[] poses string[] erases }}, - TopicSpec Marker{ message { uint8 ARROW=0 uint8 CUBE=1 uint8 SPHERE=2 uint8 CYLINDER=3 uint8 LINE_STRIP=4 uint8 LINE_LIST=5 uint8 CUBE_LIST=6 uint8 SPHERE_LIST=7 uint8 POINTS=8 uint8 TEXT_VIEW_FACING=9 uint8 MESH_RESOURCE=10 uint8 TRIANGLE_LIST=11 uint8 ADD=0 uint8 MODIFY=0 uint8 DELETE=2 uint8 DELETEALL=3 Header header string ns int32 id int32 type int32 action "geometry_msgs.Pose" pose "geometry_msgs.Vector3" scale "std_msgs.ColorRGBA" color duration lifetime bool frame_locked "geometry_msgs.Point"[] points "std_msgs.ColorRGBA"[] colors string text string mesh_resource bool mesh_use_embedded_materials }}, - TopicSpec MarkerArray{ message { Marker[] markers }}, - TopicSpec MenuEntry{ message { uint32 id uint32 parent_id string title string command uint8 FEEDBACK=0 uint8 ROSRUN=1 uint8 ROSLAUNCH=2 uint8 command_type }} - }} -} \ No newline at end of file +actionlib_msgs: + specs: + msg: GoalID + message: + time stamp string id + msg: GoalStatus + message: + GoalID goal_id uint8 status uint8 PENDING=0 uint8 ACTIVE=1 uint8 PREEMPTED=2 uint8 SUCCEEDED=3 uint8 ABORTED=4 uint8 REJECTED=5 uint8 PREEMPTING=6 uint8 RECALLING=7 uint8 RECALLED=8 uint8 LOST=9 string text + msg: GoalStatusArray + message: + Header header GoalStatus[] status_list +diagnostic_msgs: + specs: + msg: DiagnosticArray + message: + Header header DiagnosticStatus[] status + msg: DiagnosticStatus + message: + byte OK=0 byte WARN=1 byte ERROR=2 byte STALE=3 byte level string name string message string hardware_id KeyValue[] values + msg: KeyValue + message: + string key string value + srv: AddDiagnostics + request: + string load_namespace + + response: + bool success string message + srv: SelfTest + request: + + response: + string id byte passed DiagnosticStatus[] status +geometry_msgs: + specs: + msg: Accel + message: + Vector3 linear Vector3 angular + msg: AccelStamped + message: + Header header Accel accel + msg: AccelWithCovariance + message: + Accel accel float64[] covariance + msg: AccelWithCovarianceStamped + message: + Header header AccelWithCovariance accel + msg: Inertia + message: + float64 m "geometry_msgs.Vector3" com float64 ixx float64 ixy float64 ixz float64 iyy float64 iyz float64 izz + msg: InertiaStamped + message: + Header header Inertia inertia + msg: Point + message: + float64 x float64 y float64 z + msg: Point32 + message: + float32 x float32 y float32 z + msg: PointStamped + message: + Header header Point point + msg: Polygon + message: + Point32[] points + msg: PolygonStamped + message: + Header header Polygon polygon + msg: Pose + message: + Point position Quaternion orientation + msg: Pose2D + message: + float64 x float64 y float64 theta + msg: PoseArray + message: + Header header Pose[] poses + msg: PoseStamped + message: + Header header Pose pose + msg: PoseWithCovariance + message: + Pose pose float64[] covariance + msg: PoseWithCovarianceStamped + message: + Header header PoseWithCovariance pose + msg: Quaternion + message: + float64 x float64 y float64 z float64 w + msg: QuaternionStamped + message: + Header header Quaternion quaternion + msg: Transform + message: + Vector3 translation Quaternion rotation + msg: TransformStamped + message: + Header header string child_frame_id Transform transform + msg: Twist + message: + Vector3 linear Vector3 angular + msg: TwistStamped + message: + Header header Twist twist + msg: TwistWithCovariance + message: + Twist twist float64[] covariance + msg: TwistWithCovarianceStamped + message: + Header header TwistWithCovariance twist + msg: Vector3 + message: + float64 x float64 y float64 z + msg: Vector3Stamped + message: + Header header Vector3 vector + msg: Wrench + message: + Vector3 force Vector3 torque + msg: WrenchStamped + message: + Header header Wrench wrench +nav_msgs: + specs: + msg: GetMapAction + message: + GetMapActionGoal action_goal GetMapActionResult action_result GetMapActionFeedback action_feedback + msg: GetMapActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status GetMapFeedback feedback + msg: GetMapActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id GetMapGoal goal + msg: GetMapActionResult + message: + Header header "actionlib_msgs.GoalStatus" status GetMapResult result + msg: GetMapFeedback + message: + + msg: GetMapGoal + message: + + msg: GetMapResult + message: + "nav_msgs.OccupancyGrid" map + msg: GridCells + message: + Header header float32 cell_width float32 cell_height "geometry_msgs.Point"[] cells + msg: MapMetaData + message: + time map_load_time float32 resolution uint32 width uint32 height "geometry_msgs.Pose" origin + msg: OccupancyGrid + message: + Header header MapMetaData info int8[] data + msg: Odometry + message: + Header header string child_frame_id "geometry_msgs.PoseWithCovariance" pose "geometry_msgs.TwistWithCovariance" twist + msg: Path + message: + Header header "geometry_msgs.PoseStamped"[] poses + srv: GetMap + request: + + response: + "nav_msgs.OccupancyGrid" map + srv: GetPlan + request: + "geometry_msgs.PoseStamped" start "geometry_msgs.PoseStamped" goal float32 tolerance + + response: + "nav_msgs.Path" plan + srv: LoadMap + request: + string map_url + + response: + uint8 RESULT_SUCCESS=0 uint8 RESULT_MAP_DOES_NOT_EXIST=1 uint8 RESULT_INVALID_MAP_DATA=2 uint8 RESULT_INVALID_MAP_METADATA=3 uint8 RESULT_UNDEFINED_FAILURE=255 "nav_msgs.OccupancyGrid" map uint8 result + srv: SetMap + request: + "nav_msgs.OccupancyGrid" map "geometry_msgs.PoseWithCovarianceStamped" initial_pose + + response: + bool success +sensor_msgs: + specs: + msg: BatteryState + message: + uint8 POWER_SUPPLY_STATUS_UNKNOWN=0 uint8 POWER_SUPPLY_STATUS_CHARGING=1 uint8 POWER_SUPPLY_STATUS_DISCHARGING=2 uint8 POWER_SUPPLY_STATUS_NOT_CHARGING=3 uint8 POWER_SUPPLY_STATUS_FULL=4 uint8 POWER_SUPPLY_HEALTH_UNKNOWN=0 uint8 POWER_SUPPLY_HEALTH_GOOD=1 uint8 POWER_SUPPLY_HEALTH_OVERHEAT=2 uint8 POWER_SUPPLY_HEALTH_DEAD=3 uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE=4 uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE=5 uint8 POWER_SUPPLY_HEALTH_COLD=6 uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE=7 uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE=8 uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN=0 uint8 POWER_SUPPLY_TECHNOLOGY_NIMH=1 uint8 POWER_SUPPLY_TECHNOLOGY_LION=2 uint8 POWER_SUPPLY_TECHNOLOGY_LIPO=3 uint8 POWER_SUPPLY_TECHNOLOGY_LIFE=4 uint8 POWER_SUPPLY_TECHNOLOGY_NICD=5 uint8 POWER_SUPPLY_TECHNOLOGY_LIMN=6 Header header float32 voltage float32 temperature float32 current float32 charge float32 capacity float32 design_capacity float32 percentage uint8 power_supply_status uint8 power_supply_health uint8 power_supply_technology bool present float32[] cell_voltage float32[] cell_temperature string location string serial_number + msg: CameraInfo + message: + Header header uint32 height uint32 width string distortion_model float64[] D float64[] K float64[] R float64[] P uint32 binning_x uint32 binning_y RegionOfInterest roi + msg: ChannelFloat32 + message: + string name float32[] values + msg: CompressedImage + message: + Header header string format uint8[] data + msg: FluidPressure + message: + Header header float64 fluid_pressure float64 variance + msg: Illuminance + message: + Header header float64 illuminance float64 variance + msg: Image + message: + Header header uint32 height uint32 width string encoding uint8 is_bigendian uint32 step uint8[] data + msg: Imu + message: + Header header "geometry_msgs.Quaternion" orientation float64[] orientation_covariance "geometry_msgs.Vector3" angular_velocity float64[] angular_velocity_covariance "geometry_msgs.Vector3" linear_acceleration float64[] linear_acceleration_covariance + msg: JointState + message: + Header header string[] name float64[] position float64[] velocity float64[] effort + msg: Joy + message: + Header header float32[] axes int32[] buttons + msg: JoyFeedback + message: + uint8 TYPE_LED=0 uint8 TYPE_RUMBLE=1 uint8 TYPE_BUZZER=2 uint8 type uint8 id float32 intensity + msg: JoyFeedbackArray + message: + JoyFeedback[] array + msg: LaserEcho + message: + float32[] echoes + msg: LaserScan + message: + Header header float32 angle_min float32 angle_max float32 angle_increment float32 time_increment float32 scan_time float32 range_min float32 range_max float32[] ranges float32[] intensities + msg: MagneticField + message: + Header header "geometry_msgs.Vector3" magnetic_field float64[] magnetic_field_covariance + msg: MultiDOFJointState + message: + Header header string[] joint_names "geometry_msgs.Transform"[] transforms "geometry_msgs.Twist"[] twist "geometry_msgs.Wrench"[] wrench + msg: MultiEchoLaserScan + message: + Header header float32 angle_min float32 angle_max float32 angle_increment float32 time_increment float32 scan_time float32 range_min float32 range_max LaserEcho[] ranges LaserEcho[] intensities + msg: NavSatFix + message: + Header header NavSatStatus status float64 latitude float64 longitude float64 altitude float64[] position_covariance uint8 COVARIANCE_TYPE_UNKNOWN=0 uint8 COVARIANCE_TYPE_APPROXIMATED=1 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2 uint8 COVARIANCE_TYPE_KNOWN=3 uint8 position_covariance_type + msg: NavSatStatus + message: + int8 STATUS_NO_FIX=-1 int8 STATUS_FIX=0 int8 STATUS_SBAS_FIX=1 int8 STATUS_GBAS_FIX=2 int8 status uint16 SERVICE_GPS=1 uint16 SERVICE_GLONASS=2 uint16 SERVICE_COMPASS=4 uint16 SERVICE_GALILEO=8 uint16 service + msg: PointCloud + message: + Header header "geometry_msgs.Point32"[] points ChannelFloat32[] channels + msg: PointCloud2 + message: + Header header uint32 height uint32 width PointField[] fields bool is_bigendian uint32 point_step uint32 row_step uint8[] data bool is_dense + msg: PointField + message: + uint8 INT8=1 uint8 UINT8=2 uint8 INT16=3 uint8 UINT16=4 uint8 INT32=5 uint8 UINT32=6 uint8 FLOAT32=7 uint8 FLOAT64=8 string name uint32 offset uint8 datatype uint32 count + msg: Range + message: + Header header uint8 ULTRASOUND=0 uint8 INFRARED=1 uint8 radiation_type float32 field_of_view float32 min_range float32 max_range float32 range + msg: RegionOfInterest + message: + uint32 x_offset uint32 y_offset uint32 height uint32 width bool do_rectify + msg: RelativeHumidity + message: + Header header float64 relative_humidity float64 variance + msg: Temperature + message: + Header header float64 temperature float64 variance + msg: TimeReference + message: + Header header time time_ref string source + srv: SetCameraInfo + request: + "sensor_msgs.CameraInfo" camera_info + + response: + bool success string status_message +shape_msgs: + specs: + msg: Mesh + message: + MeshTriangle[] triangles "geometry_msgs.Point"[] vertices + msg: MeshTriangle + message: + uint32[] vertex_indices + msg: Plane + message: + float64[] coef + msg: SolidPrimitive + message: + uint8 BOX=1 uint8 SPHERE=2 uint8 CYLINDER=3 uint8 CONE=4 uint8 type float64[] dimensions uint8 BOX_X=0 uint8 BOX_Y=1 uint8 BOX_Z=2 uint8 SPHERE_RADIUS=0 uint8 CYLINDER_HEIGHT=0 uint8 CYLINDER_RADIUS=1 uint8 CONE_HEIGHT=0 uint8 CONE_RADIUS=1 +stereo_msgs: + specs: + msg: DisparityImage + message: + Header header "sensor_msgs.Image" image float32 f float32 T "sensor_msgs.RegionOfInterest" valid_window float32 min_disparity float32 max_disparity float32 delta_d +trajectory_msgs: + specs: + msg: JointTrajectory + message: + Header header string[] joint_names JointTrajectoryPoint[] points + msg: JointTrajectoryPoint + message: + float64[] positions float64[] velocities float64[] accelerations float64[] effort duration time_from_start + msg: MultiDOFJointTrajectory + message: + Header header string[] joint_names MultiDOFJointTrajectoryPoint[] points + msg: MultiDOFJointTrajectoryPoint + message: + "geometry_msgs.Transform"[] transforms "geometry_msgs.Twist"[] velocities "geometry_msgs.Twist"[] accelerations duration time_from_start +visualization_msgs: + specs: + msg: ImageMarker + message: + uint8 CIRCLE=0 uint8 LINE_STRIP=1 uint8 LINE_LIST=2 uint8 POLYGON=3 uint8 POINTS=4 uint8 ADD=0 uint8 REMOVE=1 Header header string ns int32 id int32 type int32 action "geometry_msgs.Point" position float32 scale "std_msgs.ColorRGBA" outline_color uint8 filled "std_msgs.ColorRGBA" fill_color duration lifetime "geometry_msgs.Point"[] points "std_msgs.ColorRGBA"[] outline_colors + msg: InteractiveMarker + message: + Header header "geometry_msgs.Pose" pose string name string description float32 scale MenuEntry[] menu_entries InteractiveMarkerControl[] controls + msg: InteractiveMarkerControl + message: + string name "geometry_msgs.Quaternion" orientation uint8 INHERIT=0 uint8 FIXED=1 uint8 VIEW_FACING=2 uint8 orientation_mode uint8 NONE=0 uint8 MENU=1 uint8 BUTTON=2 uint8 MOVE_AXIS=3 uint8 MOVE_PLANE=4 uint8 ROTATE_AXIS=5 uint8 MOVE_ROTATE=6 uint8 MOVE_3D=7 uint8 ROTATE_3D=8 uint8 MOVE_ROTATE_3D=9 uint8 interaction_mode bool always_visible Marker[] markers bool independent_marker_orientation string description + msg: InteractiveMarkerFeedback + message: + Header header string client_id string marker_name string control_name uint8 KEEP_ALIVE=0 uint8 POSE_UPDATE=1 uint8 MENU_SELECT=2 uint8 BUTTON_CLICK=3 uint8 MOUSE_DOWN=4 uint8 MOUSE_UP=5 uint8 event_type "geometry_msgs.Pose" pose uint32 menu_entry_id "geometry_msgs.Point" mouse_point bool mouse_point_valid + msg: InteractiveMarkerInit + message: + string server_id uint64 seq_num InteractiveMarker[] markers + msg: InteractiveMarkerPose + message: + Header header "geometry_msgs.Pose" pose string name + msg: InteractiveMarkerUpdate + message: + string server_id uint64 seq_num uint8 KEEP_ALIVE=0 uint8 UPDATE=1 uint8 type InteractiveMarker[] markers InteractiveMarkerPose[] poses string[] erases + msg: Marker + message: + uint8 ARROW=0 uint8 CUBE=1 uint8 SPHERE=2 uint8 CYLINDER=3 uint8 LINE_STRIP=4 uint8 LINE_LIST=5 uint8 CUBE_LIST=6 uint8 SPHERE_LIST=7 uint8 POINTS=8 uint8 TEXT_VIEW_FACING=9 uint8 MESH_RESOURCE=10 uint8 TRIANGLE_LIST=11 uint8 ADD=0 uint8 MODIFY=0 uint8 DELETE=2 uint8 DELETEALL=3 Header header string ns int32 id int32 type int32 action "geometry_msgs.Pose" pose "geometry_msgs.Vector3" scale "std_msgs.ColorRGBA" color duration lifetime bool frame_locked "geometry_msgs.Point"[] points "std_msgs.ColorRGBA"[] colors string text string mesh_resource bool mesh_use_embedded_materials + msg: MarkerArray + message: + Marker[] markers + msg: MenuEntry + message: + uint32 id uint32 parent_id string title string command uint8 FEEDBACK=0 uint8 ROSRUN=1 uint8 ROSLAUNCH=2 uint8 command_type diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/control_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/control_msgs.ros index 6e65cfc..9c8e3cb 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/control_msgs.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/control_msgs.ros @@ -1,48 +1,136 @@ -PackageSet{ - Package control_msgs{ Specs { - TopicSpec FollowJointTrajectoryAction{ message { FollowJointTrajectoryActionGoal action_goal FollowJointTrajectoryActionResult action_result FollowJointTrajectoryActionFeedback action_feedback }}, - TopicSpec FollowJointTrajectoryActionFeedback{ message { Header header "actionlib_msgs.GoalStatus" status FollowJointTrajectoryFeedback feedback }}, - TopicSpec FollowJointTrajectoryActionGoal{ message { Header header "actionlib_msgs.GoalID" goal_id FollowJointTrajectoryGoal goal }}, - TopicSpec FollowJointTrajectoryActionResult{ message { Header header "actionlib_msgs.GoalStatus" status FollowJointTrajectoryResult result }}, - TopicSpec FollowJointTrajectoryFeedback{ message { Header header string[] joint_names "trajectory_msgs.JointTrajectoryPoint" desired "trajectory_msgs.JointTrajectoryPoint" actual "trajectory_msgs.JointTrajectoryPoint" error }}, - TopicSpec FollowJointTrajectoryGoal{ message { "trajectory_msgs.JointTrajectory" trajectory JointTolerance[] path_tolerance JointTolerance[] goal_tolerance duration goal_time_tolerance }}, - TopicSpec FollowJointTrajectoryResult{ message { int32 error_code int32 SUCCESSFUL=0 int32 INVALID_GOAL=-1 int32 INVALID_JOINTS=-2 int32 OLD_HEADER_TIMESTAMP=-3 int32 PATH_TOLERANCE_VIOLATED=-4 int32 GOAL_TOLERANCE_VIOLATED=-5 string error_string }}, - TopicSpec GripperCommand{ message { float64 position float64 max_effort }}, - TopicSpec GripperCommandAction{ message { GripperCommandActionGoal action_goal GripperCommandActionResult action_result GripperCommandActionFeedback action_feedback }}, - TopicSpec GripperCommandActionFeedback{ message { Header header "actionlib_msgs.GoalStatus" status GripperCommandFeedback feedback }}, - TopicSpec GripperCommandActionGoal{ message { Header header "actionlib_msgs.GoalID" goal_id GripperCommandGoal goal }}, - TopicSpec GripperCommandActionResult{ message { Header header "actionlib_msgs.GoalStatus" status GripperCommandResult result }}, - TopicSpec GripperCommandFeedback{ message { float64 position float64 effort bool stalled bool reached_goal }}, - TopicSpec GripperCommandGoal{ message { GripperCommand command }}, - TopicSpec GripperCommandResult{ message { float64 position float64 effort bool stalled bool reached_goal }}, - TopicSpec JointControllerState{ message { Header header float64 set_point float64 process_value float64 process_value_dot float64 error float64 time_step float64 command float64 p float64 i float64 d float64 i_clamp bool antiwindup }}, - TopicSpec JointJog{ message { Header header string[] joint_names float64[] displacements float64[] velocities float64 duration }}, - TopicSpec JointTolerance{ message { string name float64 position float64 velocity float64 acceleration }}, - TopicSpec JointTrajectoryAction{ message { JointTrajectoryActionGoal action_goal JointTrajectoryActionResult action_result JointTrajectoryActionFeedback action_feedback }}, - TopicSpec JointTrajectoryActionFeedback{ message { Header header "actionlib_msgs.GoalStatus" status JointTrajectoryFeedback feedback }}, - TopicSpec JointTrajectoryActionGoal{ message { Header header "actionlib_msgs.GoalID" goal_id JointTrajectoryGoal goal }}, - TopicSpec JointTrajectoryActionResult{ message { Header header "actionlib_msgs.GoalStatus" status JointTrajectoryResult result }}, - TopicSpec JointTrajectoryControllerState{ message { Header header string[] joint_names "trajectory_msgs.JointTrajectoryPoint" desired "trajectory_msgs.JointTrajectoryPoint" actual "trajectory_msgs.JointTrajectoryPoint" error }}, - TopicSpec JointTrajectoryFeedback{ message { }}, - TopicSpec JointTrajectoryGoal{ message { "trajectory_msgs.JointTrajectory" trajectory }}, - TopicSpec JointTrajectoryResult{ message { }}, - TopicSpec PidState{ message { Header header duration timestep float64 error float64 error_dot float64 p_error float64 i_error float64 d_error float64 p_term float64 i_term float64 d_term float64 i_max float64 i_min float64 output }}, - TopicSpec PointHeadAction{ message { PointHeadActionGoal action_goal PointHeadActionResult action_result PointHeadActionFeedback action_feedback }}, - TopicSpec PointHeadActionFeedback{ message { Header header "actionlib_msgs.GoalStatus" status PointHeadFeedback feedback }}, - TopicSpec PointHeadActionGoal{ message { Header header "actionlib_msgs.GoalID" goal_id PointHeadGoal goal }}, - TopicSpec PointHeadActionResult{ message { Header header "actionlib_msgs.GoalStatus" status PointHeadResult result }}, - TopicSpec PointHeadFeedback{ message { float64 pointing_angle_error }}, - TopicSpec PointHeadGoal{ message { "geometry_msgs.PointStamped" target "geometry_msgs.Vector3" pointing_axis string pointing_frame duration min_duration float64 max_velocity }}, - TopicSpec PointHeadResult{ message { }}, - TopicSpec SingleJointPositionAction{ message { SingleJointPositionActionGoal action_goal SingleJointPositionActionResult action_result SingleJointPositionActionFeedback action_feedback }}, - TopicSpec SingleJointPositionActionFeedback{ message { Header header "actionlib_msgs.GoalStatus" status SingleJointPositionFeedback feedback }}, - TopicSpec SingleJointPositionActionGoal{ message { Header header "actionlib_msgs.GoalID" goal_id SingleJointPositionGoal goal }}, - TopicSpec SingleJointPositionActionResult{ message { Header header "actionlib_msgs.GoalStatus" status SingleJointPositionResult result }}, - TopicSpec SingleJointPositionFeedback{ message { Header header float64 position float64 velocity float64 error }}, - TopicSpec SingleJointPositionGoal{ message { float64 position duration min_duration float64 max_velocity }}, - TopicSpec SingleJointPositionResult{ message { }}, - ServiceSpec QueryCalibrationState{ request { } response { bool is_calibrated } }, - ServiceSpec QueryTrajectoryState{ request { time time } response { string[] name float64[] position float64[] velocity float64[] acceleration } }, - ActionSpec FollowJointTrajectory{ goal { FollowJointTrajectoryActionGoal action_goal} result {FollowJointTrajectoryActionResult action_result} feedback {FollowJointTrajectoryActionFeedback action_feedback}} - }} -} \ No newline at end of file +control_msgs: + specs: + msg: FollowJointTrajectoryAction + message: + FollowJointTrajectoryActionGoal action_goal FollowJointTrajectoryActionResult action_result FollowJointTrajectoryActionFeedback action_feedback + msg: FollowJointTrajectoryActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status FollowJointTrajectoryFeedback feedback + msg: FollowJointTrajectoryActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id FollowJointTrajectoryGoal goal + msg: FollowJointTrajectoryActionResult + message: + Header header "actionlib_msgs.GoalStatus" status FollowJointTrajectoryResult result + msg: FollowJointTrajectoryFeedback + message: + Header header string[] joint_names "trajectory_msgs.JointTrajectoryPoint" desired "trajectory_msgs.JointTrajectoryPoint" actual "trajectory_msgs.JointTrajectoryPoint" error + msg: FollowJointTrajectoryGoal + message: + "trajectory_msgs.JointTrajectory" trajectory JointTolerance[] path_tolerance JointTolerance[] goal_tolerance duration goal_time_tolerance + msg: FollowJointTrajectoryResult + message: + int32 error_code int32 SUCCESSFUL=0 int32 INVALID_GOAL=-1 int32 INVALID_JOINTS=-2 int32 OLD_HEADER_TIMESTAMP=-3 int32 PATH_TOLERANCE_VIOLATED=-4 int32 GOAL_TOLERANCE_VIOLATED=-5 string error_string + msg: GripperCommand + message: + float64 position float64 max_effort + msg: GripperCommandAction + message: + GripperCommandActionGoal action_goal GripperCommandActionResult action_result GripperCommandActionFeedback action_feedback + msg: GripperCommandActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status GripperCommandFeedback feedback + msg: GripperCommandActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id GripperCommandGoal goal + msg: GripperCommandActionResult + message: + Header header "actionlib_msgs.GoalStatus" status GripperCommandResult result + msg: GripperCommandFeedback + message: + float64 position float64 effort bool stalled bool reached_goal + msg: GripperCommandGoal + message: + GripperCommand command + msg: GripperCommandResult + message: + float64 position float64 effort bool stalled bool reached_goal + msg: JointControllerState + message: + Header header float64 set_point float64 process_value float64 process_value_dot float64 error float64 time_step float64 command float64 p float64 i float64 d float64 i_clamp bool antiwindup + msg: JointJog + message: + Header header string[] joint_names float64[] displacements float64[] velocities float64 duration + msg: JointTolerance + message: + string name float64 position float64 velocity float64 acceleration + msg: JointTrajectoryAction + message: + JointTrajectoryActionGoal action_goal JointTrajectoryActionResult action_result JointTrajectoryActionFeedback action_feedback + msg: JointTrajectoryActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status JointTrajectoryFeedback feedback + msg: JointTrajectoryActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id JointTrajectoryGoal goal + msg: JointTrajectoryActionResult + message: + Header header "actionlib_msgs.GoalStatus" status JointTrajectoryResult result + msg: JointTrajectoryControllerState + message: + Header header string[] joint_names "trajectory_msgs.JointTrajectoryPoint" desired "trajectory_msgs.JointTrajectoryPoint" actual "trajectory_msgs.JointTrajectoryPoint" error + msg: JointTrajectoryFeedback + message: + + msg: JointTrajectoryGoal + message: + "trajectory_msgs.JointTrajectory" trajectory + msg: JointTrajectoryResult + message: + + msg: PidState + message: + Header header duration timestep float64 error float64 error_dot float64 p_error float64 i_error float64 d_error float64 p_term float64 i_term float64 d_term float64 i_max float64 i_min float64 output + msg: PointHeadAction + message: + PointHeadActionGoal action_goal PointHeadActionResult action_result PointHeadActionFeedback action_feedback + msg: PointHeadActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status PointHeadFeedback feedback + msg: PointHeadActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id PointHeadGoal goal + msg: PointHeadActionResult + message: + Header header "actionlib_msgs.GoalStatus" status PointHeadResult result + msg: PointHeadFeedback + message: + float64 pointing_angle_error + msg: PointHeadGoal + message: + "geometry_msgs.PointStamped" target "geometry_msgs.Vector3" pointing_axis string pointing_frame duration min_duration float64 max_velocity + msg: PointHeadResult + message: + + msg: SingleJointPositionAction + message: + SingleJointPositionActionGoal action_goal SingleJointPositionActionResult action_result SingleJointPositionActionFeedback action_feedback + msg: SingleJointPositionActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status SingleJointPositionFeedback feedback + msg: SingleJointPositionActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id SingleJointPositionGoal goal + msg: SingleJointPositionActionResult + message: + Header header "actionlib_msgs.GoalStatus" status SingleJointPositionResult result + msg: SingleJointPositionFeedback + message: + Header header float64 position float64 velocity float64 error + msg: SingleJointPositionGoal + message: + float64 position duration min_duration float64 max_velocity + msg: SingleJointPositionResult + message: + + srv: QueryCalibrationState + request: + + response: + bool is_calibrated + srv: QueryTrajectoryState + request: + time time + + response: + string[] name float64[] position float64[] velocity float64[] acceleration diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/controller_manager_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/controller_manager_msgs.ros index f82e7f2..af4c030 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/controller_manager_msgs.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/controller_manager_msgs.ros @@ -1,14 +1,48 @@ -PackageSet{ - Package controller_manager_msgs{ Specs { - TopicSpec ControllerState{}, - TopicSpec ControllerStatistics{}, - TopicSpec ControllersStatistics{}, - TopicSpec HardwareInterfaceResources{}, - ServiceSpec ListControllerTypes{}, - ServiceSpec ListControllers{}, - ServiceSpec LoadController{}, - ServiceSpec ReloadControllerLibraries{}, - ServiceSpec SwitchController{}, - ServiceSpec UnloadController{} - }} -} +controller_manager_msgs: + specs: + msg: ControllerState + message: + string name string state string type "controller_manager_msgs.HardwareInterfaceResources"[] claimed_resources + msg: ControllerStatistics + message: + string name string type time timestamp bool running duration max_time duration mean_time duration variance_time int32 num_control_loop_overruns time time_last_control_loop_overrun + msg: ControllersStatistics + message: + "std_msgs.Header" header "controller_manager_msgs.ControllerStatistics"[] controller + msg: HardwareInterfaceResources + message: + string hardware_interface string[] resources + srv: ListControllerTypes + request: + + response: + string[] types string[] base_classes + srv: ListControllers + request: + + response: + ControllerState[] controller + srv: LoadController + request: + string name + + response: + bool ok + srv: ReloadControllerLibraries + request: + bool force_kill + + response: + bool ok + srv: SwitchController + request: + string[] start_controllers string[] stop_controllers int32 strictness int32 BEST_EFFORT=1 int32 STRICT=2 bool start_asap float64 timeout + + response: + bool ok + srv: UnloadController + request: + string name + + response: + bool ok diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/dynamic_reconfigure.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/dynamic_reconfigure.ros index cd4a67b..1454b10 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/dynamic_reconfigure.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/dynamic_reconfigure.ros @@ -1,15 +1,38 @@ -PackageSet{ - Package dynamic_reconfigure{ Specs { - TopicSpec BoolParameter{}, - TopicSpec Config{}, - TopicSpec ConfigDescription{}, - TopicSpec DoubleParameter{}, - TopicSpec Group{}, - TopicSpec GroupState{}, - TopicSpec IntParameter{}, - TopicSpec ParamDescription{}, - TopicSpec SensorLevels{}, - TopicSpec StrParameter{}, - ServiceSpec Reconfigure{} - }} -} +dynamic_reconfigure: + specs: + msg: BoolParameter + message: + string name bool value + msg: Config + message: + BoolParameter[] bools IntParameter[] ints StrParameter[] strs DoubleParameter[] doubles GroupState[] groups + msg: ConfigDescription + message: + Group[] groups Config max Config min Config dflt + msg: DoubleParameter + message: + string name float64 value + msg: Group + message: + string name string type ParamDescription[] parameters int32 parent int32 id + msg: GroupState + message: + string name bool state int32 id int32 parent + msg: IntParameter + message: + string name int32 value + msg: ParamDescription + message: + string name string type uint32 level string description string edit_method + msg: SensorLevels + message: + byte RECONFIGURE_CLOSE=3 byte RECONFIGURE_STOP=1 byte RECONFIGURE_RUNNING=0 + msg: StrParameter + message: + string name string value + srv: Reconfigure + request: + Config config + + response: + Config config diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/generate_messages_model_helper.sh b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/generate_messages_model_helper.sh index 099f457..46dbd1c 100755 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/generate_messages_model_helper.sh +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/generate_messages_model_helper.sh @@ -1,7 +1,6 @@ #!/bin/bash package_list=$@ - function parserToRosModel(){ msg_desc="" for word in $1; do @@ -20,10 +19,6 @@ function parserToRosModel(){ echo $msg_desc } -echo 'PackageSet{' -arr_pkg=($package_list) -cout_pkg=${#arr_pkg[@]} - for p in $package_list do cout_pkg=$((cout_pkg-1)) @@ -34,21 +29,19 @@ do arr_srv=($services_fullname) cout_srv=${#arr_srv[@]} - echo ' Package '$p'{ Specs { ' + echo $p':' + echo ' specs:' for i in $messages_fullname do cout_msg=$((cout_msg-1)) message=${i/$p\//} - MsgsArray+=$message' ' message_show=$(rosmsg show -r $i | sed '/^#/ d' | awk -F'#' '{print $1}') message_show="$(echo $message_show | sed -e 's/\s=\s/=/g')" final_desc=$(parserToRosModel "$message_show") - echo -n ' TopicSpec '$message'{ message { '$final_desc' }}' - if (("$cout_msg" >= "1" || "$cout_srv" >= "1" )) - then - echo ',' - fi + echo -n ' msg: '$message + echo $'\n'' message:' + echo ' '$final_desc done for i in $services_fullname @@ -60,40 +53,42 @@ do response="$(echo $service_show | sed -e 's#.*---\(\)#\1#'| sed -e 's/\s=\s/=/g')" final_request=$(parserToRosModel "$request") final_response=$(parserToRosModel "$response") - echo -n ' ServiceSpec '$service'{ request { '$final_request' } response { '$final_response' } }' - if (("$cout_srv" >= "1")) - then - echo ',' + echo -n ' srv: '$service + echo $'\n'' request:' + if [ -n "$request" ];then + echo ' '$final_request fi - done - - for i in $MsgsArray - do - if [[ "$i" =~ "ActionGoal" ]];then - ActionName=${i//'ActionGoal'/} - if [[ "${MsgsArray[@]}" =~ "${ActionName}ActionResult" ]] && [[ "${MsgsArray[@]}" =~ "${ActionName}ActionFeedback" ]]; then - arr_act+=$ActionName' ' - fi - fi - done - cout_act=${#arr_act[@]} - for i in $arr_act - do - cout_act=$((cout_act-1)) - echo -n ' ActionSpec '$i'{ goal { '$i'ActionGoal action_goal} result {'$i'ActionResult action_result} feedback {'$i'ActionFeedback action_feedback}} -' - if (("$cout_act" >= "1")) - then - echo ',' + echo $'\n'' response:' + if [ -n "$response" ];then + echo ' '$final_response fi done - - echo -n $'\n }}' - if (("$cout_pkg" >= "1")) - then - echo ',' - fi done -echo $'\n }' - +# for i in $MsgsArray +# do +# if [[ "$i" =~ "ActionGoal" ]];then +# ActionName=${i//'ActionGoal'/} +# if [[ "${MsgsArray[@]}" =~ "${ActionName}ActionResult" ]] && [[ "${MsgsArray[@]}" =~ "${ActionName}ActionFeedback" ]]; then +# arr_act+=$ActionName' ' +# fi +# fi +# done +# cout_act=${#arr_act[@]} +# for i in $arr_act +# do +# cout_act=$((cout_act-1)) +# echo -n ' ActionSpec '$i'{ goal { '$i'ActionGoal action_goal} result {'$i'ActionResult action_result} feedback {'$i'ActionFeedback action_feedback}} +#' +# if (("$cout_act" >= "1")) +# then +# echo ',' +# fi +# done +# +# echo -n $'\n }}' +# if (("$cout_pkg" >= "1")) +# then +# echo ',' +# fi +#done diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/map_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/map_msgs.ros index a0c7ed9..38fbd63 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/map_msgs.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/map_msgs.ros @@ -1,18 +1,46 @@ -PackageSet{ - Package map_msgs { Specs { - TopicSpec OccupancyGridUpdate{}, - TopicSpec PointCloud2Update{}, - TopicSpec ProjectedMap{}, - TopicSpec ProjectedMapInfo{}, - TopicSpec octoOctomap{}, - TopicSpec octoOctomapWithPose{}, - ServiceSpec GetMapROI{}, - ServiceSpec GetPointMap{}, - ServiceSpec GetPointMapROI{}, - ServiceSpec ProjectedMapsInfo{}, - ServiceSpec SaveMap{}, - ServiceSpec SetMapProjections{}, - ServiceSpec octoBoundingBoxQuery{}, - ServiceSpec octoGetOctomap{} - }} -} +map_msgs: + specs: + msg: OccupancyGridUpdate + message: + "std_msgs.Header" header int32 x int32 y uint32 width uint32 height int8[] data + msg: PointCloud2Update + message: + uint32 ADD=0 uint32 DELETE=1 "std_msgs.Header" header uint32 type "sensor_msgs.PointCloud2" points + msg: ProjectedMap + message: + "nav_msgs.OccupancyGrid" map float64 min_z float64 max_z + msg: ProjectedMapInfo + message: + string frame_id float64 x float64 y float64 width float64 height float64 min_z float64 max_z + srv: GetMapROI + request: + float64 x float64 y float64 l_x float64 l_y + + response: + "nav_msgs.OccupancyGrid" sub_map + srv: GetPointMap + request: + + response: + "sensor_msgs.PointCloud2" map + srv: GetPointMapROI + request: + float64 x float64 y float64 z float64 r float64 l_x float64 l_y float64 l_z + + response: + "sensor_msgs.PointCloud2" sub_map + srv: ProjectedMapsInfo + request: + "map_msgs.ProjectedMapInfo"[] projected_maps_info + + response: + srv: SaveMap + request: + "std_msgs.String" filename + + response: + srv: SetMapProjections + request: + + response: + "map_msgs.ProjectedMapInfo"[] projected_maps_info diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/move_base_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/move_base_msgs.ros index a252f2c..b3cfe9b 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/move_base_msgs.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/move_base_msgs.ros @@ -1,12 +1,26 @@ -PackageSet{ - Package move_base_msgs { Specs { - TopicSpec MoveBaseAction{}, - TopicSpec MoveBaseActionFeedback{}, - TopicSpec MoveBaseActionGoal{}, - TopicSpec MoveBaseActionResult{}, - TopicSpec MoveBaseFeedback{}, - TopicSpec MoveBaseGoal{}, - TopicSpec MoveBaseResult{}, - ActionSpec MoveBase{} - }} -} +move_base_msgs: + specs: + msg: MoveBaseAction + message: + MoveBaseActionGoal action_goal MoveBaseActionResult action_result MoveBaseActionFeedback action_feedback + msg: MoveBaseActionFeedback + message: + Header header "actionlib_msgs.GoalStatus" status MoveBaseFeedback feedback + msg: MoveBaseActionGoal + message: + Header header "actionlib_msgs.GoalID" goal_id MoveBaseGoal goal + msg: MoveBaseActionResult + message: + Header header "actionlib_msgs.GoalStatus" status MoveBaseResult result + msg: MoveBaseFeedback + message: + "geometry_msgs.PoseStamped" base_position + msg: MoveBaseGoal + message: + "geometry_msgs.PoseStamped" target_pose + msg: MoveBaseResult + message: + + msg: RecoveryStatus + message: + "geometry_msgs.PoseStamped" pose_stamped uint16 current_recovery_number uint16 total_number_of_recoveries string recovery_behavior_name diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros index 91a106d..b3c50d8 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros @@ -1,7 +1,19 @@ -PackageSet{ - Package nodelet { Specs { - ServiceSpec NodeletList{}, - ServiceSpec NodeletLoad{}, - ServiceSpec NodeletUnload{} - }} -} +nodelet: + specs: + srv: NodeletList + request: + + response: + string[] nodelets + srv: NodeletLoad + request: + string name string type string[] remap_source_args string[] remap_target_args string[] my_argv string bond_id + + response: + bool success + srv: NodeletUnload + request: + string name + + response: + bool success diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/ros_core.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/ros_core.ros index 737eef5..1d29410 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/ros_core.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/ros_core.ros @@ -1,40 +1,112 @@ -PackageSet{ - Package std_msgs { Specs { - TopicSpec Bool{ message { bool data }}, - TopicSpec Byte{ message { byte data }}, - TopicSpec ByteMultiArray{ message { MultiArrayLayout layout byte[] data }}, - TopicSpec ColorRGBA{ message { float32 r float32 g float32 b float32 a }}, - TopicSpec Duration{ message { duration data }}, - TopicSpec Empty{ message { }}, - TopicSpec Float32{ message { float32 data }}, - TopicSpec Float32MultiArray{ message { MultiArrayLayout layout float32[] data }}, - TopicSpec Float64{ message { float64 data }}, - TopicSpec Float64MultiArray{ message { MultiArrayLayout layout float64[] data }}, - TopicSpec Header{ message { uint32 seq time stamp string frame_id }}, - TopicSpec Int16{ message { int16 data }}, - TopicSpec Int16MultiArray{ message { MultiArrayLayout layout int16[] data }}, - TopicSpec Int32{ message { int32 data }}, - TopicSpec Int32MultiArray{ message { MultiArrayLayout layout int32[] data }}, - TopicSpec Int64{ message { int64 data }}, - TopicSpec Int64MultiArray{ message { MultiArrayLayout layout int64[] data }}, - TopicSpec Int8{ message { int8 data }}, - TopicSpec Int8MultiArray{ message { MultiArrayLayout layout int8[] data }}, - TopicSpec MultiArrayDimension{ message { string label uint32 size uint32 stride }}, - TopicSpec MultiArrayLayout{ message { MultiArrayDimension[] dim uint32 data_offset }}, - TopicSpec String{ message { string data }}, - TopicSpec Time{ message { time data }}, - TopicSpec UInt16{ message { uint16 data }}, - TopicSpec UInt16MultiArray{ message { MultiArrayLayout layout uint16[] data }}, - TopicSpec UInt32{ message { uint32 data }}, - TopicSpec UInt32MultiArray{ message { MultiArrayLayout layout uint32[] data }}, - TopicSpec UInt64{ message { uint64 data }}, - TopicSpec UInt64MultiArray{ message { MultiArrayLayout layout uint64[] data }}, - TopicSpec UInt8{ message { uint8 data }}, - TopicSpec UInt8MultiArray{ message { MultiArrayLayout layout uint8[] data }} - }}, - Package std_srvs { Specs { - ServiceSpec Empty{ request { } response { } }, - ServiceSpec SetBool{ request { bool data } response { bool success string message } }, - ServiceSpec Trigger{ request { } response { bool success string message } } - }} -} \ No newline at end of file +std_msgs: + specs: + msg: Bool + message: + bool data + msg: Byte + message: + byte data + msg: ByteMultiArray + message: + MultiArrayLayout layout byte[] data + msg: ColorRGBA + message: + float32 r float32 g float32 b float32 a + msg: Duration + message: + duration data + msg: Empty + message: + + msg: Float32 + message: + float32 data + msg: Float32MultiArray + message: + MultiArrayLayout layout float32[] data + msg: Float64 + message: + float64 data + msg: Float64MultiArray + message: + MultiArrayLayout layout float64[] data + msg: Header + message: + uint32 seq time stamp string frame_id + msg: Int16 + message: + int16 data + msg: Int16MultiArray + message: + MultiArrayLayout layout int16[] data + msg: Int32 + message: + int32 data + msg: Int32MultiArray + message: + MultiArrayLayout layout int32[] data + msg: Int64 + message: + int64 data + msg: Int64MultiArray + message: + MultiArrayLayout layout int64[] data + msg: Int8 + message: + int8 data + msg: Int8MultiArray + message: + MultiArrayLayout layout int8[] data + msg: MultiArrayDimension + message: + string label uint32 size uint32 stride + msg: MultiArrayLayout + message: + MultiArrayDimension[] dim uint32 data_offset + msg: String + message: + string data + msg: Time + message: + time data + msg: UInt16 + message: + uint16 data + msg: UInt16MultiArray + message: + MultiArrayLayout layout uint16[] data + msg: UInt32 + message: + uint32 data + msg: UInt32MultiArray + message: + MultiArrayLayout layout uint32[] data + msg: UInt64 + message: + uint64 data + msg: UInt64MultiArray + message: + MultiArrayLayout layout uint64[] data + msg: UInt8 + message: + uint8 data + msg: UInt8MultiArray + message: + MultiArrayLayout layout uint8[] data +std_srvs: + specs: + srv: Empty + request: + + response: + srv: SetBool + request: + bool data + + response: + bool success string message + srv: Trigger + request: + + response: + bool success string message diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/theora_image_transport.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/theora_image_transport.ros index 3d85406..fc2e21b 100644 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/theora_image_transport.ros +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/theora_image_transport.ros @@ -1,6 +1,5 @@ -PackageSet{ - Package theora_image_transport{ Specs { - TopicSpec Packet{} - }} - -} +theora_image_transport: + specs: + msg: Packet + message: + Header header uint8[] data int32 b_o_s int32 e_o_s int64 granulepos int64 packetno diff --git a/de.fraunhofer.ipa.ros.communication.objects/components/joy_node.componentinterface b/de.fraunhofer.ipa.ros.communication.objects/components/joy_node.componentinterface deleted file mode 100644 index c2319ec..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/components/joy_node.componentinterface +++ /dev/null @@ -1,8 +0,0 @@ -ComponentInterface { name joy_node - FromRosNode "joy.joy_node.joy_node" - RosPublishers{ - RosPublisher "joy" { RefPublisher "joy.joy_node.joy_node.joy"}, - RosPublisher "diagnostics" { RefPublisher "joy.joy_node.joy_node.diagnostics"} - } - -} diff --git a/de.fraunhofer.ipa.ros.communication.objects/components/joystick_teleop_node.componentinterface b/de.fraunhofer.ipa.ros.communication.objects/components/joystick_teleop_node.componentinterface deleted file mode 100644 index 560f5ca..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/components/joystick_teleop_node.componentinterface +++ /dev/null @@ -1,10 +0,0 @@ -ComponentInterface { name joystick_teleop_node - FromRosNode "teleop.joystick_teleop_node.joystick_teleop_node" - RosPublishers{ - RosPublisher "cmd_vel" { RefPublisher "teleop.joystick_teleop_node.joystick_teleop_node.cmd_vel"} - } - RosSubscribers{ - RosSubscriber "joy" { RefSubscriber "teleop.joystick_teleop_node.joystick_teleop_node.joy"} - } - -} diff --git a/de.fraunhofer.ipa.ros.communication.objects/components/scan_2d.componentinterface b/de.fraunhofer.ipa.ros.communication.objects/components/scan_2d.componentinterface deleted file mode 100644 index 71caea2..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/components/scan_2d.componentinterface +++ /dev/null @@ -1,8 +0,0 @@ -ComponentInterface { name scan_2d - FromRosNode "scan_2d.scan_2d.scan_2d" - RosPublishers{ - RosPublisher "scan" { RefPublisher "scan_2d.scan_2d.scan_2d.scan"}, - RosPublisher "diagnostics" { RefPublisher "scan_2d.scan_2d.scan_2d.diagnostics"} - } - -}