diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros deleted file mode 100644 index 10e03ad..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/Joy.ros +++ /dev/null @@ -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..5a82f41 --- /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/msg/Joy" + diagnostics: + type: "diagnostic_msgs/msg/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..2f1a9f1 --- /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/msg/LaserScan" + diagnostics: + type: "diagnostic_msgs/msg/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..5d985ca --- /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/msg/Twist" + subscribers: + joy: + type:"sensor_msgs/msg/Joy" \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_component_template.ros1 b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_component_template.ros1 new file mode 100644 index 0000000..2f176a9 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_component_template.ros1 @@ -0,0 +1,26 @@ +my_awesome_pkg: + artifacts: + awesome: + node: awesome_node_ros1 + publishers: + awesome_pub: + type: "std_msgs/msg/Bool" + subscribers: + awesome_sub: + type: "std_msgs/msg/Bool" + serviceclients: + awesome_client: + type: "std_srvs/srv/Empty" + serviceservers: + awesome_server: + type: "std_srvs/srv/Empty" + actionclients: + awesome_action: + type: "control_msgs/action/JointTrajectory" + actionservers: + awesome_action: + type: "control_msgs/action/JointTrajectory" + parameters: + awesome_param: + type: String + default: "Hello" \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_component_template.ros2 b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_component_template.ros2 new file mode 100644 index 0000000..72a4abe --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_component_template.ros2 @@ -0,0 +1,68 @@ +my_awesome_pkg: + artifacts: + awesome: + node: awesome_node + publishers: + awesome_pub: + type: "std_msgs/msg/Bool" + qos: + depth: 10 + durability: volatile + history: keep_all + profile: default_qos + reliability: best_effort + subscribers: + awesome_sub: + type: "std_msgs/msg/Bool" + qos: + depth: 10 + durability: transient_local + history: keep_last + profile: sensor_qos + reliability: reliable + serviceclients: + awesome_client: + type: "std_srvs/srv/Empty" + qos: + depth: 10 + durability: volatile + history: keep_all + profile: services_qos + reliability: best_effort + serviceservers: + awesome_server: + type: "std_srvs/srv/Empty" + qos: + depth: 10 + durability: volatile + history: keep_all + profile: services_qos + reliability: best_effort + actionclients: + awesome_action: + type: "control_msgs/action/JointTrajectory" + qos: + depth: 10 + durability: volatile + history: keep_all + profile: default_qos + reliability: best_effort + actionservers: + awesome_action: + type: "control_msgs/action/JointTrajectory" + qos: + depth: 10 + durability: volatile + history: keep_all + profile: default_qos + reliability: best_effort + parameters: + awesome_param: + type: String + default: "Hello" + qos: + depth: 10 + durability: volatile + history: keep_all + profile: parameter_qos + reliability: best_effort \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_system_template.rossystem b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_system_template.rossystem new file mode 100644 index 0000000..621b9aa --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/BasicSpecs/ros_system_template.rossystem @@ -0,0 +1,19 @@ +my_awesome_system: + processes: + process1: + nodes: [ node1 , node2 ] + threads: 2 + nodes: + node1: + from: "my_awesome_pkg.awesome_node" #From .ros2 file + interfaces: + - my_publisher: pub-> "awesome::awesome_pub" # From .ros2 file + parameters: + - my_param: "awesome::awesome_param" + value: "Label" + node2: + from: "my_awesome_pkg.awesome_node" #From .ros2 file + interfaces: + - my_subscriber: sub-> "awesome::awesome_sub" + connections: + -[my_publisher, my_subscriber] # From line 10 and 17 \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/aruco_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/aruco_msgs.ros new file mode 100644 index 0000000..df47ff8 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/aruco_msgs.ros @@ -0,0 +1,8 @@ +aruco_msgs: + msgs: + Marker + message + "std_msgs/msg/Header" header uint32 id "geometry_msgs/msg/PoseWithCovariance" pose float64 confidence + MarkerArray + message + "std_msgs/msg/Header" header "aruco_msgs/msg/Marker"[] markers diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/builtin_interfaces.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/builtin_interfaces.ros new file mode 100644 index 0000000..6a2a31d --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/builtin_interfaces.ros @@ -0,0 +1,13 @@ +builtin_interfaces: + msgs: + Time + message + int32 sec + uint32 nanosec + Duration + message + int32 sec + uint32 nanosec + + + \ 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..2860033 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,338 @@ -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: + msgs: + GoalID + message + time stamp string id + GoalStatus + message + 'actionlib_msgs/msg/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 + GoalStatusArray + message + Header header 'actionlib_msgs/msg/GoalStatus'[] status_list +diagnostic_msgs: + msgs: + DiagnosticArray + message + Header header 'diagnostic_msgs/msg/DiagnosticStatus'[] status + DiagnosticStatus + message + byte OK=0 byte WARN=1 byte ERROR=2 byte STALE=3 byte level string name string message string hardware_id 'diagnostic_msgs/msg/KeyValue'[] values + KeyValue + message + string key string value + srvs: + AddDiagnostics + request + string load_namespace + + response + bool success string message + SelfTest + request + response + string id byte passed 'diagnostic_msgs/msg/DiagnosticStatus'[] status +geometry_msgs: + msgs: + Accel + message + 'geometry_msgs/msg/Vector3' linear 'geometry_msgs/msg/Vector3' angular + AccelStamped + message + Header header 'geometry_msgs/msg/Accel' accel + AccelWithCovariance + message + 'geometry_msgs/msg/Accel' accel float64[] covariance + AccelWithCovarianceStamped + message + Header header 'geometry_msgs/msg/AccelWithCovariance' accel + Inertia + message + float64 m 'geometry_msgs/msg/Vector3' com float64 ixx float64 ixy float64 ixz float64 iyy float64 iyz float64 izz + InertiaStamped + message + Header header 'geometry_msgs/msg/Inertia' inertia + Point + message + float64 x float64 y float64 z + Point32 + message + float32 x float32 y float32 z + PointStamped + message + Header header 'geometry_msgs/msg/Point' point + Polygon + message + 'geometry_msgs/msg/Point32'[] points + PolygonStamped + message + Header header 'geometry_msgs/msg/Polygon' polygon + Pose + message + 'geometry_msgs/msg/Point' position 'geometry_msgs/msg/Quaternion' orientation + Pose2D + message + float64 x float64 y float64 theta + PoseArray + message + Header header 'geometry_msgs/msg/Pose'[] poses + PoseStamped + message + Header header 'geometry_msgs/msg/Pose' pose + PoseWithCovariance + message + 'geometry_msgs/msg/Pose' pose float64[] covariance + PoseWithCovarianceStamped + message + Header header 'geometry_msgs/msg/PoseWithCovariance' pose + Quaternion + message + float64 x float64 y float64 z float64 w + QuaternionStamped + message + Header header 'geometry_msgs/msg/Quaternion' quaternion + Transform + message + 'geometry_msgs/msg/Vector3' translation 'geometry_msgs/msg/Quaternion' rotation + TransformStamped + message + Header header string child_frame_id 'geometry_msgs/msg/Transform' transform + Twist + message + 'geometry_msgs/msg/Vector3' linear 'geometry_msgs/msg/Vector3' angular + TwistStamped + message + Header header 'geometry_msgs/msg/Twist' twist + TwistWithCovariance + message + 'geometry_msgs/msg/Twist' twist float64[] covariance + TwistWithCovarianceStamped + message + Header header 'geometry_msgs/msg/TwistWithCovariance' twist + Vector3 + message + float64 x float64 y float64 z + Vector3Stamped + message + Header header 'geometry_msgs/msg/Vector3' vector + Wrench + message + 'geometry_msgs/msg/Vector3' force 'geometry_msgs/msg/Vector3' torque + WrenchStamped + message + Header header 'geometry_msgs/msg/Wrench' wrench +nav_msgs: + msgs: + GetMapAction + message + 'nav_msgs/msg/GetMapActionGoal' action_goal 'nav_msgs/msg/GetMapActionResult' action_result 'nav_msgs/msg/GetMapActionFeedback' action_feedback + GetMapActionFeedback + message + Header header "actionlib_msgs/msg/GoalStatus" status 'nav_msgs/msg/GetMapFeedback' feedback + GetMapActionGoal + message + Header header "actionlib_msgs/msg/GoalID" goal_id 'nav_msgs/msg/GetMapGoal' goal + GetMapActionResult + message + Header header "actionlib_msgs/msg/GoalStatus" status 'nav_msgs/msg/GetMapResult' result + GetMapFeedback + message + + GetMapGoal + message + + GetMapResult + message + "nav_msgs/msg/OccupancyGrid" map + GridCells + message + Header header float32 cell_width float32 cell_height "geometry_msgs/msg/Point"[] cells + MapMetaData + message + time map_load_time float32 resolution uint32 width uint32 height "geometry_msgs/msg/Pose" origin + OccupancyGrid + message + Header header 'nav_msgs/msg/MapMetaData' info int8[] data + Odometry + message + Header header string child_frame_id "geometry_msgs/msg/PoseWithCovariance" pose "geometry_msgs/msg/TwistWithCovariance" twist + Path + message + Header header "geometry_msgs/msg/PoseStamped"[] poses + srvs: + GetMap + request + + response + "nav_msgs/msg/OccupancyGrid" map + GetPlan + request + "geometry_msgs/msg/PoseStamped" start "geometry_msgs/msg/PoseStamped" goal float32 tolerance + + response + "nav_msgs/msg/Path" plan + 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/msg/OccupancyGrid" map uint8 result + SetMap + request + "nav_msgs/msg/OccupancyGrid" map "geometry_msgs/msg/PoseWithCovarianceStamped" initial_pose + + response + bool success +sensor_msgs: + msgs: + 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 + 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 'sensor_msgs/msg/RegionOfInterest' roi + ChannelFloat32 + message + string name float32[] values + CompressedImage + message + Header header string format uint8[] data + FluidPressure + message + Header header float64 fluid_pressure float64 variance + Illuminance + message + Header header float64 illuminance float64 variance + Image + message + Header header uint32 height uint32 width string encoding uint8 is_bigendian uint32 step uint8[] data + Imu + message + Header header "geometry_msgs/msg/Quaternion" orientation float64[] orientation_covariance "geometry_msgs/msg/Vector3" angular_velocity float64[] angular_velocity_covariance "geometry_msgs/msg/Vector3" linear_acceleration float64[] linear_acceleration_covariance + JointState + message + Header header string[] name float64[] position float64[] velocity float64[] effort + Joy + message + Header header float32[] axes int32[] buttons + JoyFeedback + message + uint8 TYPE_LED=0 uint8 TYPE_RUMBLE=1 uint8 TYPE_BUZZER=2 uint8 type uint8 id float32 intensity + JoyFeedbackArray + message + 'sensor_msgs/msg/JoyFeedback'[] array + LaserEcho + message + float32[] echoes + 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 + MagneticField + message + Header header "geometry_msgs/msg/Vector3" magnetic_field float64[] magnetic_field_covariance + MultiDOFJointState + message + Header header string[] joint_names "geometry_msgs/msg/Transform"[] transforms "geometry_msgs/msg/Twist"[] twist "geometry_msgs/msg/Wrench"[] wrench + 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 'sensor_msgs/msg/LaserEcho'[] ranges 'sensor_msgs/msg/LaserEcho'[] intensities + NavSatFix + message + Header header 'sensor_msgs/msg/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 + 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 + PointCloud + message + Header header "geometry_msgs/msg/Point32"[] points 'sensor_msgs/msg/ChannelFloat32'[] channels + PointCloud2 + message + Header header uint32 height uint32 width 'sensor_msgs/msg/PointField'[] fields bool is_bigendian uint32 point_step uint32 row_step uint8[] data bool is_dense + 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 + 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 + RegionOfInterest + message + uint32 x_offset uint32 y_offset uint32 height uint32 width bool do_rectify + RelativeHumidity + message + Header header float64 relative_humidity float64 variance + Temperature + message + Header header float64 temperature float64 variance + TimeReference + message + Header header time time_ref string source + srvs: + SetCameraInfo + request + "sensor_msgs/msg/CameraInfo" camera_info + response + bool success string status_message +shape_msgs: + msgs: + Mesh + message + 'shape_msgs/msg/MeshTriangle'[] triangles "geometry_msgs/msg/Point"[] vertices + MeshTriangle + message + uint32[] vertex_indices + Plane + message + float64[] coef + 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: + msgs: + DisparityImage + message + Header header "sensor_msgs/msg/Image" image float32 f float32 T "sensor_msgs/msg/RegionOfInterest" valid_window float32 min_disparity float32 max_disparity float32 delta_d +trajectory_msgs: + msgs: + JointTrajectory + message + Header header string[] joint_names 'trajectory_msgs/msg/JointTrajectoryPoint'[] points + JointTrajectoryPoint + message + float64[] positions float64[] velocities float64[] accelerations float64[] effort duration time_from_start + MultiDOFJointTrajectory + message + Header header string[] joint_names 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] points + MultiDOFJointTrajectoryPoint + message + "geometry_msgs/msg/Transform"[] transforms "geometry_msgs/msg/Twist"[] velocities "geometry_msgs/msg/Twist"[] accelerations duration time_from_start +visualization_msgs: + msgs: + 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/msg/Point" position float32 scale "std_msgs/msg/ColorRGBA" outline_color uint8 filled "std_msgs/msg/ColorRGBA" fill_color duration lifetime "geometry_msgs/msg/Point"[] points "std_msgs/msg/ColorRGBA"[] outline_colors + InteractiveMarker + message + Header header "geometry_msgs/msg/Pose" pose string name string description float32 scale 'visualization_msgs/msg/MenuEntry'[] menu_entries 'visualization_msgs/msg/InteractiveMarkerControl'[] controls + InteractiveMarkerControl + message + string name "geometry_msgs/msg/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 'visualization_msgs/msg/Marker'[] markers bool independent_marker_orientation string description + 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/msg/Pose" pose uint32 menu_entry_id "geometry_msgs/msg/Point" mouse_point bool mouse_point_valid + InteractiveMarkerInit + message + string server_id uint64 seq_num 'visualization_msgs/msg/InteractiveMarker'[] markers + InteractiveMarkerPose + message + Header header "geometry_msgs/msg/Pose" pose string name + InteractiveMarkerUpdate + message + string server_id uint64 seq_num uint8 KEEP_ALIVE=0 uint8 UPDATE=1 uint8 type 'visualization_msgs/msg/InteractiveMarker'[] markers 'visualization_msgs/msg/InteractiveMarkerPose'[] poses string[] erases + 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/msg/Pose" pose "geometry_msgs/msg/Vector3" scale "std_msgs/msg/ColorRGBA" color duration lifetime bool frame_locked "geometry_msgs/msg/Point"[] points "std_msgs/msg/ColorRGBA"[] colors string text string mesh_resource bool mesh_use_embedded_materials + MarkerArray + message + 'visualization_msgs/msg/Marker'[] markers + 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..04c933f 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,181 @@ -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: + msgs: + DynamicJointState + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'control_msgs/msg/InterfaceValue'[] interface_values + AdmittanceControllerState + message + 'std_msgs/msg/Float64MultiArray'[] mass + 'std_msgs/msg/Float64MultiArray'[] damping + 'std_msgs/msg/Float64MultiArray'[] stiffness + 'geometry_msgs/msg/Quaternion'[] rot_base_control + 'geometry_msgs/msg/TransformStamped'[] ref_trans_base_ft + 'std_msgs/msg/Int8MultiArray'[] selected_axes + 'std_msgs/msg/String'[] ft_sensor_frame + 'geometry_msgs/msg/TransformStamped'[] admittance_position + 'geometry_msgs/msg/TwistStamped'[] admittance_acceleration + 'geometry_msgs/msg/TwistStamped'[] admittance_velocity + 'geometry_msgs/msg/WrenchStamped'[] wrench_base + 'sensor_msgs/msg/JointState'[] joint_state + JointComponentTolerance + message + string joint_name + uint16 component + float64 position + float64 velocity + float64 acceleration + JointControllerState + message + 'std_msgs/msg/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 + InterfaceValue + message + string[] interface_names + float64[] values + PidState + message + 'std_msgs/msg/Header'[] header + 'builtin_interfaces/msg/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 + JointJog + message + 'std_msgs/msg/Header'[] header + string[] joint_names + float64[] displacements + float64[] velocities + float64 duration + MecanumDriveControllerState + message + 'std_msgs/msg/Header'[] header + float64 front_left_wheel_velocity + float64 back_left_wheel_velocity + float64 back_right_wheel_velocity + float64 front_right_wheel_velocity + 'geometry_msgs/msg/Twist'[] reference_velocity + JointTrajectoryControllerState + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'trajectory_msgs/msg/JointTrajectoryPoint'[] desired + 'trajectory_msgs/msg/JointTrajectoryPoint'[] actual + 'trajectory_msgs/msg/JointTrajectoryPoint'[] error + string[] multi_dof_joint_names + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_desired + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_actual + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_error + SteeringControllerStatus + message + 'std_msgs/msg/Header'[] header + float64[] traction_wheels_position + float64[] traction_wheels_velocity + float64[] steer_positions + float64[] linear_velocity_command + float64[] steering_angle_command + JointTolerance + message + string name + float64 position + float64 velocity + float64 acceleration + + srvs: + QueryTrajectoryState + request + 'builtin_interfaces/msg/Time'[] time + response + bool success + string message + string[] name + float64[] position + float64[] velocity + float64[] acceleration + QueryCalibrationState + request + response + bool is_calibrated + + actions: + JointTrajectory + goal + 'trajectory_msgs/msg/JointTrajectory'[] trajectory + result + feedback + PointHead + goal + 'geometry_msgs/msg/PointStamped'[] target + 'geometry_msgs/msg/Vector3'[] pointing_axis + string pointing_frame + 'builtin_interfaces/msg/Duration'[] min_duration + float64 max_velocity + result + feedback + float64 pointing_angle_error + FollowJointTrajectory + goal + 'trajectory_msgs/msg/JointTrajectory'[] trajectory + 'trajectory_msgs/msg/MultiDOFJointTrajectory'[] multi_dof_trajectory + 'control_msgs/msg/JointTolerance'[] path_tolerance + 'control_msgs/msg/JointComponentTolerance'[] component_path_tolerance + 'control_msgs/msg/JointTolerance'[] goal_tolerance + 'control_msgs/msg/JointComponentTolerance'[] component_goal_tolerance + 'builtin_interfaces/msg/Duration'[] goal_time_tolerance + result + int32 error_code + string error_string + feedback + 'std_msgs/msg/Header'[] header + string[] joint_names + 'trajectory_msgs/msg/JointTrajectoryPoint'[] desired + 'trajectory_msgs/msg/JointTrajectoryPoint'[] actual + 'trajectory_msgs/msg/JointTrajectoryPoint'[] error + string[] multi_dof_joint_names + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_desired + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_actual + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_error + SingleJointPosition + goal + float64 position + 'builtin_interfaces/msg/Duration'[] min_duration + float64 max_velocity + result + feedback + 'std_msgs/msg/Header'[] header + float64 position + float64 velocity + float64 error + GripperCommand + goal + 'control_msgs/msg/GripperCommand'[] command + result + float64 position + float64 effort + bool stalled + bool reached_goal + feedback + float64 position + float64 effort + bool stalled + bool reached_goal + \ No newline at end of file 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..7c06b25 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,92 @@ -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: + msgs: + ControllerState + message + string name + string state + string type + string[] claimed_interfaces + string[] required_command_interfaces + string[] required_state_interfaces + bool is_chainable + bool is_chained + string[] reference_interfaces + 'controller_manager_msgs/msg/ChainConnection'[] chain_connections + ChainConnection + message + string name + string[] reference_interfaces + HardwareComponentState + message + string name + string type + string class_type + 'lifecycle_msgs/msg/State'[] state + 'controller_manager_msgs/msg/HardwareInterface'[] command_interfaces + 'controller_manager_msgs/msg/HardwareInterface'[] state_interfaces + HardwareInterface + message + string name + bool is_available + bool is_claimed + + srvs: + ListControllerTypes + request + response + string[] types + string[] base_classes + SwitchController + request + string[] activate_controllers + string[] deactivate_controllers + string[] start_controllers + string[] stop_controllers + int32 strictness + bool start_asap + bool activate_asap + 'builtin_interfaces/msg/Duration'[] timeout + response + bool ok + ListHardwareComponents + request + response + 'controller_manager_msgs/msg/HardwareComponentState'[] component + SetHardwareComponentState + request + string name + 'lifecycle_msgs/msg/State'[] target_state + response + bool ok + 'lifecycle_msgs/msg/State'[] state + LoadController + request + string name + response + bool ok + UnloadController + request + string name + response + bool ok + ReloadControllerLibraries + request + bool force_kill + response + bool ok + ListControllers + request + response + 'controller_manager_msgs/msg/ControllerState'[] controller + ListHardwareInterfaces + request + response + 'controller_manager_msgs/msg/HardwareInterface'[] command_interfaces + 'controller_manager_msgs/msg/HardwareInterface'[] state_interfaces + ConfigureController + request + string name + response + bool ok + + \ No newline at end of file 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 deleted file mode 100644 index cd4a67b..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/dynamic_reconfigure.ros +++ /dev/null @@ -1,15 +0,0 @@ -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{} - }} -} diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/gazebo_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/gazebo_msgs.ros new file mode 100644 index 0000000..0662a82 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/gazebo_msgs.ros @@ -0,0 +1,217 @@ +gazebo_msgs: + msgs: + WheelSlip + message + # This is a message that holds data to describe the wheel slip for a set of wheels. # # The wheel slip is defined by # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros the lateral slip of the wheel, as an angle from the direction of travel (radians), and # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros the longitudinal slip of the wheel, as a percentage of the current wheel's speed # # Each wheel is uniquely identified by its name. # # This message consists of multiple arrays. # All arrays in this message should be the same size. # This is the only way to uniquely associate the wheel name with the correct slip values. string[] name float64[] lateral_slip float64[] longitudinal_slip + EntityState + message + # Holds an entity's pose and twist string name # Entity's scoped name. # An entity can be a model, link, collision, light, etc. # Be sure to use gazebo scoped naming notation (e.g. []) "geometry_msgs.Pose" pose # Pose in reference frame. "geometry_msgs.Twist" twist # Twist in reference frame. string reference_frame # "Pose.twist" are expressed relative to the frame of this entity. # Leaving empty or "world" defaults to inertial world frame. + ModelStates + message + # broadcast all model states in world frame string[] name # model names "geometry_msgs.Pose"[] pose # desired pose in world frame "geometry_msgs.Twist"[] twist # desired twist in world frame + ODEPhysics + message + bool auto_disable_bodies # enable auto disabling of bodies, default false uint32 sor_pgs_precon_iters # preconditioning inner iterations when uisng projected Gauss Seidel uint32 sor_pgs_iters # inner iterations when uisng projected Gauss Seidel float64 sor_pgs_w # relaxation parameter when using projected Gauss Seidel, 1=no relaxation float64 sor_pgs_rms_error_tol # rms error tolerance before stopping inner iterations float64 contact_surface_layer # contact "dead-band" width float64 contact_max_correcting_vel # contact maximum correction velocity float64 cfm # global constraint force mixing float64 erp # global error reduction parameter uint32 max_contacts # maximum contact joints between two geoms + SensorPerformanceMetric + message + string name float64 sim_update_rate float64 real_update_rate float64 fps + WorldState + message + # This is a message that holds data necessary to reconstruct a snapshot of the world # #=Approach to Message Passing=# The state of the world is defined by either # 1. Inertial Model pose, twist # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros kinematic data - connectivity graph from Model to each Link # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros joint angles # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros joint velocities # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros Applied forces - Body wrench # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros relative transform from Body to each collision Geom # Or # 2. Inertial (absolute) Body pose, twist, wrench # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros relative transform from Body to each collision Geom - constant, so not sent over wire # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros back compute from canonical body info to get Model pose and twist. # # Chooing (2.) because it matches most physics engines out there # and is simpler. # #=Future=# Consider impacts on using reduced coordinates "." graph "(parent.child" links) approach # constraint and physics solvers. # #=Application=# This message is used to do the following: # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros reconstruct the world and objects for sensor generation # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros stop "." start simulation - need pose, twist, wrench of each body # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros collision detection - need pose of each collision geometry. "velocity.acceleration" if # #=Assumptions=# Assuming that each (physics) processor node locally already has # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros collision information - Trimesh for Geoms, etc # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros relative transforms from Body to Geom - this is assumed to be fixed, do not send oved wire # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros inertial information - does not vary in time # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros visual information - does not vary in time # "std_msgs.Header" header string[] name "geometry_msgs.Pose"[] pose "geometry_msgs.Twist"[] twist "geometry_msgs.Wrench"[] wrench + LinkStates + message + # broadcast all link states in world frame string[] name # link names "geometry_msgs.Pose"[] pose # desired pose in world frame "geometry_msgs.Twist"[] twist # desired twist in world frame + PerformanceMetrics + message + "std_msgs/msg/Header" header float64 real_time_factor "gazebo_msgs/msg/SensorPerformanceMetric"[] sensors + ContactState + message + string info # text info on this contact string collision1_name # name of contact collision1 string collision2_name # name of contact collision2 "geometry_msgs.Wrench"[] wrenches # list of "forces.torques""geometry_msgs.Wrench" total_wrench # sum of "forces.torques" in every DOF "geometry_msgs.Vector3"[] contact_positions # list of contact position "geometry_msgs.Vector3"[] contact_normals # list of contact normals float64[] depths # list of penetration depths + LinkState + message + # Deprecated, kept for ROS 1 bridge. # Use EntityState # @todo: FIXME: sets pose and twist of a link. All children link "poses.twists" of the URDF tree are not updated accordingly, but should be. string link_name # link name, link_names are in gazebo scoped name notation, [] "geometry_msgs.Pose" pose # desired pose in reference frame "geometry_msgs.Twist" twist # desired twist in reference frame string reference_frame # set "pose.twist" relative to the frame of this "link.body" # leave empty or "world" or "map" defaults to world-frame + ModelState + message + # Deprecated, kept for ROS 1 bridge. # Use EntityState # Set Gazebo Model pose and twist string model_name # model to set state (pose and twist) "geometry_msgs.Pose" pose # desired pose in reference frame "geometry_msgs.Twist" twist # desired twist in reference frame string reference_frame # set "pose.twist" relative to the frame of this entity "(Body.Model)" # leave empty or "world" or "map" defaults to world-frame + ODEJointProperties + message + # access to low level joint properties, change these at your own risk float64[] damping # joint damping float64[] hi_stop # joint limit float64[] lo_stop # joint limit float64[] erp # set joint erp float64[] cfm # set joint cfm float64[] stop_erp # set joint erp for joint limit "contact" joint float64[] stop_cfm # set joint cfm for joint limit "contact" joint float64[] fudge_factor # joint fudge_factor applied at limits, see ODE manual for info. float64[] fmax # ode joint param fmax float64[] vel # ode joint param vel + ContactsState + message + "std_msgs/msg/Header" header # stamp "gazebo_msgs.ContactState"[] states # array of geom pairs in contact + + srvs: + SetLinkProperties + request + string link_name # name of link # link names are prefixed by model name, e.g. pr2::base_link "geometry_msgs.Pose" com # center of mass location in link frame # and orientation of the moment of inertias # relative to the link frame bool gravity_mode # set gravity mode "on.off" float64 mass # linear mass of link float64 ixx # moment of inertia float64 ixy # moment of inertia float64 ixz # moment of inertia float64 iyy # moment of inertia float64 iyz # moment of inertia float64 izz # moment of inertia + + response + bool success # return true if get info is successful string status_message # comments if available + SetJointTrajectory + request + # Deprecated, kept for ROS 1 bridge. string model_name "trajectory_msgs.JointTrajectory" joint_trajectory "geometry_msgs.Pose" model_pose bool set_model_pose bool disable_physics_updates # defaults to false + + response + bool success # return true if set wrench successful string status_message # comments if available + GetModelList + request + + response + "std_msgs/msg/Header" header # Standard metadata for higher-level stamped data types. # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros header.stamp Simulation time when data was collected. string[] model_names # list of models in the world bool success # return true if get successful + GetModelProperties + request + string model_name # name of Gazebo Model + + response + string parent_model_name # parent model string canonical_body_name # name of canonical link, link names are prefixed by model name, e.g. pr2::base_link string[] body_names # list of links, link names are prefixed by model name, e.g. pr2::base_link string[] geom_names # list of collisions string[] joint_names # list of joints attached to the model string[] child_model_names # list of child models bool is_static # returns true if model is static bool success # return true if get successful string status_message # comments if available + JointRequest + request + string joint_name # name of the joint requested + + response + GetModelState + request + # Deprecated, kept for ROS 1 bridge. # Use GetEntityState string model_name # name of Gazebo Model string relative_entity_name # return pose and twist relative to this entity # an entity can be a model, body, or geom # be sure to use gazebo scoped naming notation (e.g. []) # leave empty or "world" will use inertial world frame + + response + "std_msgs/msg/Header" header # Standard metadata for higher-level stamped data types. # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros header.seq holds the number of requests since the plugin started # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros header.stamp timestamp related to the pose # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros header.frame_id not used but currently filled with the relative_entity_name "geometry_msgs.Pose" pose # pose of model in relative entity frame "geometry_msgs.Twist" twist # twist of model in relative entity frame bool success # return true if get successful string status_message # comments if available + SetLightProperties + request + string light_name # name of Gazebo Light "std_msgs.ColorRGBA" diffuse # diffuse color as red, green, blue, alpha float64 attenuation_constant float64 attenuation_linear float64 attenuation_quadratic + + response + bool success # return true if get successful string status_message # comments if available + SpawnEntity + request + string name # Name of the entity to be spawned (optional). string xml # Entity XML description as a string, either URDF or SDF. string robot_namespace # Spawn robot and all ROS interfaces under this namespace "geometry_msgs.Pose" initial_pose # Initial entity pose. string reference_frame # initial_pose is defined relative to the frame of this entity. # If left empty or "world" or "map", then gazebo world frame is # used. # If non-existent entity is specified, an error is returned # and the entity is not spawned. + + response + bool success # Return true if spawned successfully. string status_message # Comments if available. + SetJointProperties + request + string joint_name # name of joint "gazebo_msgs.ODEJointProperties" ode_joint_config # access to ODE joint dynamics properties + + response + bool success # return true if get successful string status_message # comments if available + ApplyJointEffort + request + # set urdf joint effort string joint_name # joint to apply wrench (linear force and torque) float64 effort # effort to apply "builtin_interfaces.Time" start_time # optional wrench application start time (seconds) # if start_time < current time, start as soon as possible "builtin_interfaces.Duration" duration # optional duration of wrench application time (seconds) # if duration < 0, apply wrench continuously without end # if duration=0, do nothing # if duration < step size, assume step size and # display warning in status_message + + response + bool success # return true if effort application is successful string status_message # comments if available + GetWorldProperties + request + # Deprecated, kept for ROS 1 bridge. # Use GetModelList + + response + float64 sim_time # current sim time string[] model_names # list of models in the world bool rendering_enabled # if X is used bool success # return true if get successful string status_message # comments if available + DeleteLight + request + # Deprecated, kept for ROS 1 bridge. # Use DeleteEntity string light_name # name of the light to be deleted + + response + bool success # return true if deletion is successful string status_message # comments if available + DeleteModel + request + # Deprecated, kept for ROS 1 bridge. # Use DeleteEntity string model_name # name of the Gazebo Model to be deleted + + response + bool success # return true if deletion is successful string status_message # comments if available + SpawnModel + request + # Deprecated, kept for ROS 1 bridge. # Use SpawnEntity string model_name # name of the model to be spawn string model_xml # this should be an urdf or gazebo xml string robot_namespace # spawn robot and all ROS interfaces under this namespace "geometry_msgs.Pose" initial_pose # only applied to canonical body string reference_frame # initial_pose is defined relative to the frame of this "model.body" # if left empty or "world", then gazebo world frame is used # if non-existent "model.body" is specified, an error is returned # and the model is not spawned + + response + bool success # return true if spawn successful string status_message # comments if available + GetLinkState + request + # Deprecated, kept for ROS 1 bridge. # Use GetEntityState string link_name # name of link # link names are prefixed by model name, e.g. pr2::base_link string reference_frame # reference frame of returned information, must be a valid link # if empty, use inertial (gazebo world) frame # reference_frame names are prefixed by model name, e.g. pr2::base_link + + response + "gazebo_msgs/msg/LinkState" link_state bool success # return true if get info is successful string status_message # comments if available + GetEntityState + request + string name # Entity's scoped name. # An entity can be a model, link, collision, light, etc. # Be sure to use gazebo scoped naming notation (e.g. []) string reference_frame # Return pose and twist relative to this entity. # Leaving empty or "world" will use inertial world frame. + + response + "std_msgs/msg/Header" header # Standard metadata for higher-level stamped data types. # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros header.stamp Timestamp related to the pose. # builtin_interfaces.ros common_msgs.ros controller_manager_msgs.ros control_msgs.ros gazebo_msgs.ros generate_messages_model_helper_ros1.sh generate_messages_model_helper.sh lifecycle_msgs.ros map_msgs.ros nav_msgs.ros ros_core.ros turtlesim.ros header.frame_id Filled with the relative_frame. "gazebo_msgs.EntityState" state # Contains pose and twist. bool success # Return true if get was successful. If false, the state contains garbage. + SetLinkState + request + # Deprecated, kept for ROS 1 bridge. # Use SetEntityState "gazebo_msgs.LinkState" link_state + + response + bool success # return true if set wrench successful string status_message # comments if available + SetPhysicsProperties + request + # sets pose and twist of a link. All children link "poses.twists" of the URDF tree will be updated accordingly float64 time_step # dt in seconds float64 max_update_rate # throttle maximum physics update rate "geometry_msgs.Vector3" gravity # gravity vector (e.g. earth ~[]) "gazebo_msgs.ODEPhysics" ode_config # configurations for ODE + + response + bool success # return true if set wrench successful string status_message # comments if available + SetModelState + request + # Deprecated, kept for ROS 1 bridge. # Use SetEntityState "gazebo_msgs.ModelState" model_state + + response + bool success # return true if setting state successful string status_message # comments if available + SetModelConfiguration + request + # Set joint positions for a model string model_name # model to set state string urdf_param_name # UNUSED string[] joint_names # list of joints to set positions. if joint is not listed here, preserve current position. float64[] joint_positions # set to this position. + + response + bool success # return true if setting state successful string status_message # comments if available + GetLightProperties + request + string light_name # name of Gazebo Light + + response + "std_msgs/msg/ColorRGBA" diffuse # diffuse color as red, green, blue, alpha float64 attenuation_constant float64 attenuation_linear float64 attenuation_quadratic bool success # return true if get successful string status_message # comments if available + BodyRequest + request + # Deprecated, kept for ROS 1 bridge. # Use LinkRequest string body_name # name of the body requested. body names are prefixed by model name, e.g. pr2::base_link + + response + ApplyBodyWrench + request + # Deprecated, kept for ROS 1 bridge. # Use ApplyLinkWrench # Apply Wrench to Gazebo Body. # via the callback mechanism # all Gazebo operations are made in world frame string body_name # Gazebo body to apply wrench (linear force and torque) # wrench is applied in the gazebo world by default # body names are prefixed by model name, e.g. pr2::base_link string reference_frame # wrench is defined in the reference frame of this entity # use inertial frame if left empty # frame names are bodies prefixed by model name, e.g. pr2::base_link "geometry_msgs.Point" reference_point # wrench is defined at this location in the reference frame "geometry_msgs.Wrench" wrench # wrench applied to the origin of the body "builtin_interfaces.Time" start_time # (optional) wrench application start time (seconds) # if start_time is not specified, or # start_time < current time, start as soon as possible "builtin_interfaces.Duration" duration # optional duration of wrench application time (seconds) # if duration < 0, apply wrench continuously without end # if duration=0, do nothing # if duration < step size, apply wrench # for one step size + + response + bool success # return true if set wrench successful string status_message # comments if available + GetPhysicsProperties + request + + response + # sets pose and twist of a link. All children link "poses.twists" of the URDF tree will be updated accordingly float64 time_step # dt in seconds bool pause # true if physics engine is paused float64 max_update_rate # throttle maximum physics update rate "geometry_msgs.Vector3" gravity # gravity vector (e.g. earth ~[]) "gazebo_msgs.ODEPhysics" ode_config # contains physics configurations pertaining to ODE bool success # return true if set wrench successful string status_message # comments if available + LinkRequest + request + string link_name # name of the link requested. link names are prefixed by model name, e.g. pr2::base_link + + response + DeleteEntity + request + string name # Name of the Gazebo entity to be deleted. This can be either # a model or a light. + + response + bool success # Return true if deletion is successful. string status_message # Comments if available. + GetJointProperties + request + string joint_name # Scoped name of joint + + response + # joint type uint8 type uint8 REVOLUTE=0 # single DOF uint8 CONTINUOUS=1 # single DOF (revolute "w.o" limits) uint8 PRISMATIC=2 # single DOF uint8 FIXED=3 # 0 DOF uint8 BALL=4 # 3 DOF movement, 0 DOF control uint8 UNIVERSAL=5 # 2 DOF # dynamics properties float64[] damping # joint state float64[] position float64[] rate # TODO(chapulina) Rename to velocity # service return status bool success # return true if get successful string status_message # comments if available + SetEntityState + request + "gazebo_msgs/msg/EntityState" state # Entity state to set to. # Be sure to fill all fields, values of zero have meaning. + + response + bool success # Return true if setting state was successful. + ApplyLinkWrench + request + # Apply Wrench to Gazebo Link. # via the callback mechanism # all Gazebo operations are made in world frame string link_name # Gazebo link to apply wrench (linear force and torque) # wrench is applied in the gazebo world by default # link names are prefixed by model name, e.g. pr2::base_link string reference_frame # wrench is defined in the reference frame of this entity # use inertial frame if left empty # frame names are links prefixed by model name, e.g. pr2::base_link "geometry_msgs.Point" reference_point # wrench is defined at this location in the reference frame "geometry_msgs.Wrench" wrench # wrench applied to the origin of the link "builtin_interfaces.Time" start_time # (optional) wrench application start time (seconds) # if start_time is not specified, or # start_time < current time, start as soon as possible "builtin_interfaces.Duration" duration # optional duration of wrench application time (seconds) # if duration < 0, apply wrench continuously without end # if duration=0, do nothing # if duration < step size, apply wrench # for one step size + + response + bool success # return true if set wrench successful string status_message # comments if available + GetLinkProperties + request + string link_name # name of link # link names are prefixed by model name, e.g. pr2::base_link + response + "geometry_msgs/msg/Pose" com # center of mass location in link frame # and orientation of the moment of inertias # relative to the link frame bool gravity_mode # set gravity mode "on.off" float64 mass # linear mass of link float64 ixx # moment of inertia float64 ixy # moment of inertia float64 ixz # moment of inertia float64 iyy # moment of inertia float64 iyz # moment of inertia float64 izz # moment of inertia bool success # return true if get info is successful string status_message # comments if available 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..f2f8e0d 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,80 +19,72 @@ 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)) - messages_fullname=$(rosmsg package $p) - arr_msg=($messages_fullname) - cout_msg=${#arr_msg[@]} - services_fullname=$(rossrv package $p) - arr_srv=($services_fullname) - cout_srv=${#arr_srv[@]} + specs_fullname=$(ros2 interface package $p) + arr_specs=($specs_fullname) + cout_specs=${#arr_specs[@]} - echo ' Package '$p'{ Specs { ' + echo $p':' + echo ' specs:' - for i in $messages_fullname + for i in $specs_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 ',' + cout_specs=$((cout_specs-1)) + if [[ "$i" == *"/msg"* ]]; then + message=${i/$p\/msg\//} + message_show=$(ros2 interface show $i | grep -v ' ' ) + message_show="$(echo $message_show | sed -e 's/\s=\s/=/g')" + final_desc=$(parserToRosModel "$message_show") + echo -n ' msg: '$message + echo $'\n'' message:' + echo ' '$final_desc fi - done - - for i in $services_fullname - do - cout_srv=$((cout_srv-1)) - service=${i/$p\//} - service_show=$(rossrv show -r $i | sed '/^#/ d' | awk -F'#' '{print $1}') - request="$(echo $service_show | sed 's/---.*//' | sed -e 's/\s=\s/=/g')" - 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 ',' + if [[ "$i" == *"/srv"* ]]; then + service=${i/$p\/srv\//} + service_show=$(ros2 interface show $i | grep -v ' ' ) + request="$(echo $service_show | sed 's/---.*//' | sed -e 's/\s=\s/=/g')" + response="$(echo $service_show | sed -e 's#.*---\(\)#\1#'| sed -e 's/\s=\s/=/g')" + final_request=$(parserToRosModel "$request") + final_response=$(parserToRosModel "$response") + echo -n ' srv: '$service + echo $'\n'' request:' + if [ -n "$request" ];then + echo ' '$final_request + fi + echo $'\n'' response:' + if [ -n "$response" ];then + echo ' '$final_response + fi 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 ',' - 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/generate_messages_model_helper_ros1.sh b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/generate_messages_model_helper_ros1.sh new file mode 100755 index 0000000..46dbd1c --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/generate_messages_model_helper_ros1.sh @@ -0,0 +1,94 @@ +#!/bin/bash +package_list=$@ + +function parserToRosModel(){ + msg_desc="" + for word in $1; do + word="$(echo $word | sed -e 's/\[[^][]*\]/[]/g' )" + if [[ $word == *"/"* ]]; then + ref="$(echo $word | tr / .)" + if [[ $ref = *"[]"* ]]; then + msg_desc+='"'${ref%"[]"}'"[]' + else + msg_desc+='"'$ref'"' + fi + else + msg_desc+=" "$word" " + fi + done + echo $msg_desc +} + +for p in $package_list +do + cout_pkg=$((cout_pkg-1)) + messages_fullname=$(rosmsg package $p) + arr_msg=($messages_fullname) + cout_msg=${#arr_msg[@]} + services_fullname=$(rossrv package $p) + arr_srv=($services_fullname) + cout_srv=${#arr_srv[@]} + + echo $p':' + echo ' specs:' + + for i in $messages_fullname + do + cout_msg=$((cout_msg-1)) + message=${i/$p\//} + 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 ' msg: '$message + echo $'\n'' message:' + echo ' '$final_desc + done + + for i in $services_fullname + do + cout_srv=$((cout_srv-1)) + service=${i/$p\//} + service_show=$(rossrv show -r $i | sed '/^#/ d' | awk -F'#' '{print $1}') + request="$(echo $service_show | sed 's/---.*//' | sed -e 's/\s=\s/=/g')" + response="$(echo $service_show | sed -e 's#.*---\(\)#\1#'| sed -e 's/\s=\s/=/g')" + final_request=$(parserToRosModel "$request") + final_response=$(parserToRosModel "$response") + echo -n ' srv: '$service + echo $'\n'' request:' + if [ -n "$request" ];then + echo ' '$final_request + fi + echo $'\n'' response:' + if [ -n "$response" ];then + echo ' '$final_response + fi + done +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 ',' +# fi +# done +# +# echo -n $'\n }}' +# if (("$cout_pkg" >= "1")) +# then +# echo ',' +# fi +#done diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/lifecycle_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/lifecycle_msgs.ros new file mode 100644 index 0000000..a92d006 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/lifecycle_msgs.ros @@ -0,0 +1,42 @@ +lifecycle_msgs: + msgs: + TransitionDescription + message + 'lifecycle_msgs/msg/Transition'[] transition + 'lifecycle_msgs/msg/State'[] start_state + 'lifecycle_msgs/msg/State'[] goal_state + Transition + message + uint8 id + string label + TransitionEvent + message + uint64 timestamp + 'lifecycle_msgs/msg/Transition'[] transition + 'lifecycle_msgs/msg/State'[] start_state + 'lifecycle_msgs/msg/State'[] goal_state + State + message + uint8 id + string label + + srvs: + ChangeState + request + 'lifecycle_msgs/msg/Transition'[] transition + response + bool success + GetState + request + response + 'lifecycle_msgs/msg/State'[] current_state + GetAvailableTransitions + request + response + 'lifecycle_msgs/msg/TransitionDescription'[] available_transitions + GetAvailableStates + request + response + 'lifecycle_msgs/msg/State'[] available_states + + \ No newline at end of file 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..db589b5 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,64 @@ -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: + msgs: + ProjectedMap + message + 'nav_msgs/msg/OccupancyGrid'[] map + float64 min_z + float64 max_z + PointCloud2Update + message + 'std_msgs/msg/Header'[] header + uint32 type + 'sensor_msgs/msg/PointCloud2'[] points + OccupancyGridUpdate + message + 'std_msgs/msg/Header'[] header + int32 x + int32 y + uint32 width + uint32 height + int8[] data + ProjectedMapInfo + message + string frame_id + float64 x + float64 y + float64 width + float64 height + float64 min_z + float64 max_z + + srvs: + GetPointMapROI + request + float64 x + float64 y + float64 z + response + 'sensor_msgs/msg/PointCloud2'[] sub_map + ProjectedMapsInfo + request + 'map_msgs/msg/ProjectedMapInfo'[] projected_maps_info + response + GetPointMap + request + response + 'sensor_msgs/msg/PointCloud2'[] map + SaveMap + request + 'std_msgs/msg/String'[] filename + response + SetMapProjections + request + response + 'map_msgs/msg/ProjectedMapInfo'[] projected_maps_info + GetMapROI + request + float64 x + float64 y + float64 l_x + float64 l_y + response + 'nav_msgs/msg/OccupancyGrid'[] sub_map + + \ No newline at end of file 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 deleted file mode 100644 index a252f2c..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/move_base_msgs.ros +++ /dev/null @@ -1,12 +0,0 @@ -PackageSet{ - Package move_base_msgs { Specs { - TopicSpec MoveBaseAction{}, - TopicSpec MoveBaseActionFeedback{}, - TopicSpec MoveBaseActionGoal{}, - TopicSpec MoveBaseActionResult{}, - TopicSpec MoveBaseFeedback{}, - TopicSpec MoveBaseGoal{}, - TopicSpec MoveBaseResult{}, - ActionSpec MoveBase{} - }} -} diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/moveit_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/moveit_msgs.ros new file mode 100644 index 0000000..ec138e3 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/moveit_msgs.ros @@ -0,0 +1,575 @@ +moveit_msgs: + msgs: + RobotState + message + 'sensor_msgs/msg/JointState'[] joint_state + 'sensor_msgs/msg/MultiDOFJointState'[] multi_dof_joint_state + 'moveit_msgs/msg/AttachedCollisionObject'[] attached_collision_objects + bool is_diff + RobotTrajectory + message + 'trajectory_msgs/msg/JointTrajectory'[] joint_trajectory + 'trajectory_msgs/msg/MultiDOFJointTrajectory'[] multi_dof_joint_trajectory + KinematicSolverInfo + message + string[] joint_names + 'moveit_msgs/msg/JointLimits'[] limits + string[] link_names + MotionPlanRequest + message + 'moveit_msgs/msg/WorkspaceParameters'[] workspace_parameters + 'moveit_msgs/msg/RobotState'[] start_state + 'moveit_msgs/msg/Constraints'[] goal_constraints + 'moveit_msgs/msg/Constraints'[] path_constraints + 'moveit_msgs/msg/TrajectoryConstraints'[] trajectory_constraints + 'moveit_msgs/msg/GenericTrajectory'[] reference_trajectories + string pipeline_id + string planner_id + string group_name + int32 num_planning_attempts + float64 allowed_planning_time + float64 max_velocity_scaling_factor + float64 max_acceleration_scaling_factor + string cartesian_speed_end_effector_link + float64 max_cartesian_speed + PlannerParams + message + string[] keys + string[] values + string[] descriptions + PositionIKRequest + message + string group_name + 'moveit_msgs/msg/RobotState'[] robot_state + 'moveit_msgs/msg/Constraints'[] constraints + bool avoid_collisions + string ik_link_name + 'geometry_msgs/msg/PoseStamped'[] pose_stamped + string[] ik_link_names + 'geometry_msgs/msg/PoseStamped'[] pose_stamped_vector + 'builtin_interfaces/msg/Duration'[] timeout + JointLimits + message + string joint_name + bool has_position_limits + float64 min_position + float64 max_position + bool has_velocity_limits + float64 max_velocity + bool has_acceleration_limits + float64 max_acceleration + bool has_jerk_limits + float64 max_jerk + AllowedCollisionMatrix + message + string[] entry_names + 'moveit_msgs/msg/AllowedCollisionEntry'[] entry_values + string[] default_entry_names + bool[] default_entry_values + Constraints + message + string name + 'moveit_msgs/msg/JointConstraint'[] joint_constraints + 'moveit_msgs/msg/PositionConstraint'[] position_constraints + 'moveit_msgs/msg/OrientationConstraint'[] orientation_constraints + 'moveit_msgs/msg/VisibilityConstraint'[] visibility_constraints + PositionConstraint + message + 'std_msgs/msg/Header'[] header + string link_name + 'geometry_msgs/msg/Vector3'[] target_point_offset + 'moveit_msgs/msg/BoundingVolume'[] constraint_region + float64 weight + LinkPadding + message + string link_name + float64 padding + MotionPlanDetailedResponse + message + 'moveit_msgs/msg/RobotState'[] trajectory_start + string group_name + 'moveit_msgs/msg/RobotTrajectory'[] trajectory + string[] description + float64[] processing_time + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + ContactInformation + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Point'[] position + 'geometry_msgs/msg/Vector3'[] normal + float64 depth + string contact_body_1 + uint32 body_type_1 + string contact_body_2 + uint32 body_type_2 + PlaceLocation + message + string id + 'trajectory_msgs/msg/JointTrajectory'[] post_place_posture + 'geometry_msgs/msg/PoseStamped'[] place_pose + float64 quality + 'moveit_msgs/msg/GripperTranslation'[] pre_place_approach + 'moveit_msgs/msg/GripperTranslation'[] post_place_retreat + string[] allowed_touch_objects + TrajectoryConstraints + message + 'moveit_msgs/msg/Constraints'[] constraints + PlanningOptions + message + 'moveit_msgs/msg/PlanningScene'[] planning_scene_diff + bool plan_only + bool look_around + int32 look_around_attempts + float64 max_safe_execution_cost + bool replan + int32 replan_attempts + float64 replan_delay + ObjectColor + message + string id + 'std_msgs/msg/ColorRGBA'[] color + CartesianPoint + message + 'geometry_msgs/msg/Pose'[] pose + 'geometry_msgs/msg/Twist'[] velocity + 'geometry_msgs/msg/Accel'[] acceleration + DisplayRobotState + message + 'moveit_msgs/msg/RobotState'[] state + 'moveit_msgs/msg/ObjectColor'[] highlight_links + bool hide + PlanningScene + message + string name + 'moveit_msgs/msg/RobotState'[] robot_state + string robot_model_name + 'geometry_msgs/msg/TransformStamped'[] fixed_frame_transforms + 'moveit_msgs/msg/AllowedCollisionMatrix'[] allowed_collision_matrix + 'moveit_msgs/msg/LinkPadding'[] link_padding + 'moveit_msgs/msg/LinkScale'[] link_scale + 'moveit_msgs/msg/ObjectColor'[] object_colors + 'moveit_msgs/msg/PlanningSceneWorld'[] world + bool is_diff + ConstraintEvalResult + message + bool result + float64 distance + JointConstraint + message + string joint_name + float64 position + float64 tolerance_above + float64 tolerance_below + float64 weight + BoundingVolume + message + 'shape_msgs/msg/SolidPrimitive'[] primitives + 'geometry_msgs/msg/Pose'[] primitive_poses + 'shape_msgs/msg/Mesh'[] meshes + 'geometry_msgs/msg/Pose'[] mesh_poses + LinkScale + message + string link_name + float64 scale + CartesianTrajectory + message + 'std_msgs/msg/Header'[] header + string tracked_frame + 'moveit_msgs/msg/CartesianTrajectoryPoint'[] points + MotionSequenceRequest + message + 'moveit_msgs/msg/MotionSequenceItem'[] items + VisibilityConstraint + message + float64 target_radius + 'geometry_msgs/msg/PoseStamped'[] target_pose + int32 cone_sides + 'geometry_msgs/msg/PoseStamped'[] sensor_pose + float64 max_view_angle + float64 max_range_angle + uint8 sensor_view_direction + float64 weight + WorkspaceParameters + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Vector3'[] min_corner + 'geometry_msgs/msg/Vector3'[] max_corner + MotionSequenceResponse + message + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + 'moveit_msgs/msg/RobotState'[] sequence_start + 'moveit_msgs/msg/RobotTrajectory'[] planned_trajectories + float64 planning_time + CostSource + message + float64 cost_density + 'geometry_msgs/msg/Vector3'[] aabb_min + 'geometry_msgs/msg/Vector3'[] aabb_max + PlannerInterfaceDescription + message + string name + string pipeline_id + string[] planner_ids + AttachedCollisionObject + message + string link_name + 'moveit_msgs/msg/CollisionObject'[] object + string[] touch_links + 'trajectory_msgs/msg/JointTrajectory'[] detach_posture + float64 weight + OrientedBoundingBox + message + 'geometry_msgs/msg/Pose'[] pose + 'geometry_msgs/msg/Point32'[] extents + Grasp + message + string id + 'trajectory_msgs/msg/JointTrajectory'[] pre_grasp_posture + 'trajectory_msgs/msg/JointTrajectory'[] grasp_posture + 'geometry_msgs/msg/PoseStamped'[] grasp_pose + float64 grasp_quality + 'moveit_msgs/msg/GripperTranslation'[] pre_grasp_approach + 'moveit_msgs/msg/GripperTranslation'[] post_grasp_retreat + 'moveit_msgs/msg/GripperTranslation'[] post_place_retreat + float32 max_contact_force + string[] allowed_touch_objects + PlanningSceneWorld + message + 'moveit_msgs/msg/CollisionObject'[] collision_objects + 'octomap_msgs/msg/OctomapWithPose'[] octomap + MoveItErrorCodes + message + int32 val + AllowedCollisionEntry + message + bool[] enabled + OrientationConstraint + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Quaternion'[] orientation + string link_name + float64 absolute_x_axis_tolerance + float64 absolute_y_axis_tolerance + float64 absolute_z_axis_tolerance + uint8 parameterization + float64 weight + CollisionObject + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose'[] pose + string id + 'object_recognition_msgs/msg/ObjectType'[] type + 'shape_msgs/msg/SolidPrimitive'[] primitives + 'geometry_msgs/msg/Pose'[] primitive_poses + 'shape_msgs/msg/Mesh'[] meshes + 'geometry_msgs/msg/Pose'[] mesh_poses + 'shape_msgs/msg/Plane'[] planes + 'geometry_msgs/msg/Pose'[] plane_poses + string[] subframe_names + 'geometry_msgs/msg/Pose'[] subframe_poses + byte operation + GripperTranslation + message + 'geometry_msgs/msg/Vector3Stamped'[] direction + float32 desired_distance + float32 min_distance + MotionPlanResponse + message + 'moveit_msgs/msg/RobotState'[] trajectory_start + string group_name + 'moveit_msgs/msg/RobotTrajectory'[] trajectory + float64 planning_time + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + CartesianTrajectoryPoint + message + 'moveit_msgs/msg/CartesianPoint'[] point + 'builtin_interfaces/msg/Duration'[] time_from_start + DisplayTrajectory + message + string model_id + 'moveit_msgs/msg/RobotTrajectory'[] trajectory + 'moveit_msgs/msg/RobotState'[] trajectory_start + GenericTrajectory + message + 'std_msgs/msg/Header'[] header + 'trajectory_msgs/msg/JointTrajectory'[] joint_trajectory + 'moveit_msgs/msg/CartesianTrajectory'[] cartesian_trajectory + PlanningSceneComponents + message + uint32 components + MotionSequenceItem + message + 'moveit_msgs/msg/MotionPlanRequest'[] req + float64 blend_radius + + srvs: + SaveMap + request + string filename + response + bool success + GraspPlanning + request + string group_name + 'moveit_msgs/msg/CollisionObject'[] target + string[] support_surfaces + 'moveit_msgs/msg/Grasp'[] candidate_grasps + 'moveit_msgs/msg/CollisionObject'[] movable_obstacles + response + 'moveit_msgs/msg/Grasp'[] grasps + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + GetStateValidity + request + 'moveit_msgs/msg/RobotState'[] robot_state + string group_name + 'moveit_msgs/msg/Constraints'[] constraints + response + bool valid + 'moveit_msgs/msg/ContactInformation'[] contacts + 'moveit_msgs/msg/CostSource'[] cost_sources + 'moveit_msgs/msg/ConstraintEvalResult'[] constraint_result + GetRobotStateFromWarehouse + request + string name + string robot + response + 'moveit_msgs/msg/RobotState'[] state + UpdatePointcloudOctomap + request + 'sensor_msgs/msg/PointCloud2'[] cloud + response + bool success + GetMotionSequence + request + 'moveit_msgs/msg/MotionSequenceRequest'[] "request" + response + 'moveit_msgs/msg/MotionSequenceResponse'[] "response" + ExecuteKnownTrajectory + request + 'moveit_msgs/msg/RobotTrajectory'[] trajectory + bool wait_for_execution + response + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + ApplyPlanningScene + request + 'moveit_msgs/msg/PlanningScene'[] scene + response + bool success + GetPositionIK + request + 'moveit_msgs/msg/PositionIKRequest'[] ik_request + response + 'moveit_msgs/msg/RobotState'[] solution + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + GetPlanningScene + request + 'moveit_msgs/msg/PlanningSceneComponents'[] components + response + 'moveit_msgs/msg/PlanningScene'[] scene + ListRobotStatesInWarehouse + request + string regex + string robot + response + string[] states + LoadMap + request + string filename + response + bool success + ChangeControlDimensions + request + bool control_x_translation + bool control_y_translation + bool control_z_translation + bool control_x_rotation + bool control_y_rotation + bool control_z_rotation + response + bool success + GetPlannerParams + request + string pipeline_id + string planner_config + string group + response + 'moveit_msgs/msg/PlannerParams'[] params + RenameRobotStateInWarehouse + request + string old_name + string new_name + string robot + response + QueryPlannerInterfaces + request + response + 'moveit_msgs/msg/PlannerInterfaceDescription'[] planner_interfaces + GetPositionFK + request + 'std_msgs/msg/Header'[] header + string[] fk_link_names + 'moveit_msgs/msg/RobotState'[] robot_state + response + 'geometry_msgs/msg/PoseStamped'[] pose_stamped + string[] fk_link_names + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + DeleteRobotStateFromWarehouse + request + string name + string robot + response + SetPlannerParams + request + string pipeline_id + string planner_config + string group + 'moveit_msgs/msg/PlannerParams'[] params + bool replace + response + GetMotionPlan + request + 'moveit_msgs/msg/MotionPlanRequest'[] motion_plan_request + response + 'moveit_msgs/msg/MotionPlanResponse'[] motion_plan_response + CheckIfRobotStateExistsInWarehouse + request + string name + string robot + response + bool exists + GetCartesianPath + request + 'std_msgs/msg/Header'[] header + 'moveit_msgs/msg/RobotState'[] start_state + string group_name + string link_name + 'geometry_msgs/msg/Pose'[] waypoints + float64 max_step + float64 jump_threshold + float64 prismatic_jump_threshold + float64 revolute_jump_threshold + bool avoid_collisions + 'moveit_msgs/msg/Constraints'[] path_constraints + response + 'moveit_msgs/msg/RobotState'[] start_state + 'moveit_msgs/msg/RobotTrajectory'[] solution + float64 fraction + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + ChangeDriftDimensions + request + bool drift_x_translation + bool drift_y_translation + bool drift_z_translation + bool drift_x_rotation + bool drift_y_rotation + bool drift_z_rotation + 'geometry_msgs/msg/Transform'[] transform_jog_frame_to_drift_frame + response + bool success + SaveRobotStateToWarehouse + request + string name + string robot + 'moveit_msgs/msg/RobotState'[] state + response + bool success + + actions: + Place + goal + string group_name + string attached_object_name + 'moveit_msgs/msg/PlaceLocation'[] place_locations + bool place_eef + string support_surface_name + bool allow_gripper_support_collision + 'moveit_msgs/msg/Constraints'[] path_constraints + string planner_id + string[] allowed_touch_objects + float64 allowed_planning_time + 'moveit_msgs/msg/PlanningOptions'[] planning_options + result + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + 'moveit_msgs/msg/RobotState'[] trajectory_start + 'moveit_msgs/msg/RobotTrajectory'[] trajectory_stages + string[] trajectory_descriptions + 'moveit_msgs/msg/PlaceLocation'[] place_location + float64 planning_time + feedback + string state + MoveGroupSequence + goal + 'moveit_msgs/msg/MotionSequenceRequest'[] "request" + 'moveit_msgs/msg/PlanningOptions'[] planning_options + result + 'moveit_msgs/msg/MotionSequenceResponse'[] "response" + feedback + string state + HybridPlanner + goal + string planning_group + 'moveit_msgs/msg/MotionSequenceRequest'[] motion_sequence + result + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + string error_message + feedback + string feedback + ExecuteTrajectory + goal + 'moveit_msgs/msg/RobotTrajectory'[] trajectory + result + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + feedback + string state + MoveGroup + goal + 'moveit_msgs/msg/MotionPlanRequest'[] "request" + 'moveit_msgs/msg/PlanningOptions'[] planning_options + result + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + 'moveit_msgs/msg/RobotState'[] trajectory_start + 'moveit_msgs/msg/RobotTrajectory'[] planned_trajectory + 'moveit_msgs/msg/RobotTrajectory'[] executed_trajectory + float64 planning_time + feedback + string state + Pickup + goal + string target_name + string group_name + string end_effector + 'moveit_msgs/msg/Grasp'[] possible_grasps + string support_surface_name + bool allow_gripper_support_collision + string[] attached_object_touch_links + bool minimize_object_distance + 'moveit_msgs/msg/Constraints'[] path_constraints + string planner_id + string[] allowed_touch_objects + float64 allowed_planning_time + 'moveit_msgs/msg/PlanningOptions'[] planning_options + result + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + 'moveit_msgs/msg/RobotState'[] trajectory_start + 'moveit_msgs/msg/RobotTrajectory'[] trajectory_stages + string[] trajectory_descriptions + 'moveit_msgs/msg/Grasp'[] grasp + float64 planning_time + feedback + string state + GlobalPlanner + goal + string planning_group + 'moveit_msgs/msg/MotionSequenceRequest'[] motion_sequence + result + 'moveit_msgs/msg/MotionPlanResponse'[] "response" + feedback + string feedback + LocalPlanner + goal + 'moveit_msgs/msg/Constraints'[] local_constraints + result + 'moveit_msgs/msg/MoveItErrorCodes'[] error_code + string error_message + feedback + string feedback diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nav_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nav_msgs.ros new file mode 100644 index 0000000..73c2627 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nav_msgs.ros @@ -0,0 +1,57 @@ +nav_msgs: + msgs: + Path + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/PoseStamped'[] poses + OccupancyGrid + message + 'std_msgs/msg/Header'[] header + 'nav_msgs/msg/MapMetaData'[] info + int8[] data + Odometry + message + 'std_msgs/msg/Header'[] header + string child_frame_id + 'geometry_msgs/msg/PoseWithCovariance'[] pose + 'geometry_msgs/msg/TwistWithCovariance'[] twist + GridCells + message + 'std_msgs/msg/Header'[] header + float32 cell_width + float32 cell_height + 'geometry_msgs/msg/Point'[] cells + MapMetaData + message + 'builtin_interfaces/msg/Time'[] map_load_time + float32 resolution + uint32 width + uint32 height + 'geometry_msgs/msg/Pose'[] origin + + srvs: + SetMap + request + 'nav_msgs/msg/OccupancyGrid'[] map + 'geometry_msgs/msg/PoseWithCovarianceStamped'[] initial_pose + response + bool success + LoadMap + request + string map_url + response + 'nav_msgs/msg/OccupancyGrid'[] map + uint8 result + GetPlan + request + 'geometry_msgs/msg/PoseStamped'[] start + 'geometry_msgs/msg/PoseStamped'[] goal + float32 tolerance + response + 'nav_msgs/msg/Path'[] plan + GetMap + request + response + 'nav_msgs/msg/OccupancyGrid'[] map + + diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros deleted file mode 100644 index 91a106d..0000000 --- a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/nodelet.ros +++ /dev/null @@ -1,7 +0,0 @@ -PackageSet{ - Package nodelet { Specs { - ServiceSpec NodeletList{}, - ServiceSpec NodeletLoad{}, - ServiceSpec NodeletUnload{} - }} -} diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/realsense2_camera_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/realsense2_camera_msgs.ros new file mode 100644 index 0000000..bf9513c --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/realsense2_camera_msgs.ros @@ -0,0 +1,17 @@ +realsense2_camera_msgs: + msgs: + Extrinsics + message + float64[] rotation float64[] translation + Metadata + message + "std_msgs/msg/Header" header string json_data + IMUInfo + message + # header.frame_id is either set to "imu_accel" or "imu_gyro" # to distinguish between "accel" and "gyro" info. "std_msgs.Header" header float64[] data float64[] noise_variances float64[] bias_variances + srvs: + DeviceInfo + request + + response + string device_name string serial_number string firmware_version string usb_type_descriptor string firmware_update_id string sensors 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..742d4c3 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,122 @@ -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: + msgs: + ColorRGBA + message + float32 r + float32 g + float32 b + float32 a + Float64MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + float64[] data + Int64MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + int64[] data + Byte + message + byte data + Int32MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + int32[] data + Header + message + 'builtin_interfaces/msg/Time'[] stamp + string frame_id + Int32 + message + int32 data + Float32MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + float32[] data + Int64 + message + int64 data + String + message + string data + Int16MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + int16[] data + Int8MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + int8[] data + MultiArrayLayout + message + 'std_msgs/msg/MultiArrayDimension'[] dim + uint32 data_offset + UInt16MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + uint16[] data + ByteMultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + byte[] data + Float32 + message + float32 data + UInt32MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + uint32[] data + UInt64MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + uint64[] data + MultiArrayDimension + message + string label + uint32 size + uint32 stride + UInt32 + message + uint32 data + Empty + message + Bool + message + bool data + UInt64 + message + uint64 data + Float64 + message + float64 data + UInt8 + message + uint8 data + Int8 + message + int8 data + UInt8MultiArray + message + 'std_msgs/msg/MultiArrayLayout'[] layout + uint8[] data + Int16 + message + int16 data + UInt16 + message + uint16 data +std_srvs: + srvs: + Empty + request + response + Trigger + request + response + bool success + string message + SetBool + request + bool data + response + bool success + string message diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/tf2_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/tf2_msgs.ros new file mode 100644 index 0000000..0e1c276 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/tf2_msgs.ros @@ -0,0 +1,14 @@ +tf2_msgs: + msgs: + TF2Error + message + uint8 NO_ERROR=0 uint8 LOOKUP_ERROR=1 uint8 CONNECTIVITY_ERROR=2 uint8 EXTRAPOLATION_ERROR=3 uint8 INVALID_ARGUMENT_ERROR=4 uint8 TIMEOUT_ERROR=5 uint8 TRANSFORM_ERROR=6 uint8 error string error_string + TFMessage + message + "geometry_msgs/msg/TransformStamped"[] transforms + srvs: + FrameGraph + request + + response + string frame_yaml \ No newline at end of file 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..70f2edc 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,11 @@ -PackageSet{ - Package theora_image_transport{ Specs { - TopicSpec Packet{} - }} - -} +theora_image_transport: + msgs: + Packet + message + # ROS message adaptation of the ogg_packet struct from libogg, # see "http:..www.xiph.org.ogg.doc.libogg.ogg_packet.html." + "std_msgs/msg/Header" header # Original "sensor_msgs.Image" header + uint8[] data # Raw Theora packet data (combines packet and bytes fields from ogg_packet) + int32 b_o_s # Flag indicating whether this packet begins a logical bitstream + int32 e_o_s # Flag indicating whether this packet ends a bitstream + int64 granulepos # A number indicating the position of this packet in the decoded data + int64 packetno # Sequential number of this packet in the ogg bitstream diff --git a/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/turtlesim.ros b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/turtlesim.ros new file mode 100644 index 0000000..712f571 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/basic_msgs/turtlesim.ros @@ -0,0 +1,46 @@ +turtlesim: + msgs: + Pose + message + float32 x + float32 y + float32 theta + float32 linear_velocity + float32 angular_velocity + Color + message + uint8 r + uint8 g + uint8 b + srvs: + TeleportAbsolute + request + float32 x + float32 y + float32 theta + response + SetPen + request + uint8 r + uint8 g + uint8 b + uint8 width + uint8 off + response + TeleportRelative + request + float32 linear + float32 angular + response + Spawn + request + float32 x + float32 y + float32 theta + string name # Optional. A unique name will be created and returned if this is empty + response + string name + Kill + request + string name + response 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"} - } - -} diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ackermann_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ackermann_msgs.ros new file mode 100644 index 0000000..3a4323d --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ackermann_msgs.ros @@ -0,0 +1,16 @@ +ackermann_msgs: + msgs: + AckermannDrive + message + float32 steering_angle + float32 steering_angle_velocity + float32 speed + float32 acceleration + float32 jerk + AckermannDriveStamped + message + 'std_msgs/msg/Header'[] header + 'ackermann_msgs/msg/AckermannDrive'[] drive + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/action_tutorials_interfaces.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/action_tutorials_interfaces.ros new file mode 100644 index 0000000..adf1d8e --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/action_tutorials_interfaces.ros @@ -0,0 +1,12 @@ +action_tutorials_interfaces: + + + actions: + Fibonacci + goal + int32 order + result + int32[] sequence + feedback + int32[] partial_sequence + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/actionlib_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/actionlib_msgs.ros new file mode 100644 index 0000000..6a4718b --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/actionlib_msgs.ros @@ -0,0 +1,18 @@ +actionlib_msgs: + msgs: + GoalID + message + 'builtin_interfaces/msg/Time'[] stamp + string id + GoalStatusArray + message + 'std_msgs/msg/Header'[] header + 'actionlib_msgs/msg/GoalStatus'[] status_list + GoalStatus + message + 'actionlib_msgs/msg/GoalID'[] goal_id + uint8 status + string text + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/aruco_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/aruco_msgs.ros new file mode 100644 index 0000000..4d69ec2 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/aruco_msgs.ros @@ -0,0 +1,15 @@ +aruco_msgs: + msgs: + Marker + message + 'std_msgs/msg/Header'[] header + uint32 id + 'geometry_msgs/msg/PoseWithCovariance'[] pose + float64 confidence + MarkerArray + message + 'std_msgs/msg/Header'[] header + 'aruco_msgs/msg/Marker'[] markers + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/as2_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/as2_msgs.ros new file mode 100644 index 0000000..b49d140 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/as2_msgs.ros @@ -0,0 +1,256 @@ +as2_msgs: + msgs: + ControlMode + message + 'std_msgs/msg/Header'[] header + int8 yaw_mode + int8 control_mode + int8 reference_frame + YawMode + message + uint8 mode + float32 angle + PlatformStatus + message + int8 state + TrajectoryPoint + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Vector3'[] position + 'geometry_msgs/msg/Vector3'[] twist + 'geometry_msgs/msg/Vector3'[] acceleration + float32 yaw_angle + PlatformInfo + message + 'std_msgs/msg/Header'[] header + bool connected + bool armed + bool offboard + 'as2_msgs/msg/PlatformStatus'[] status + 'as2_msgs/msg/ControlMode'[] current_control_mode + PlatformStateMachineEvent + message + int8 event + Thrust + message + 'std_msgs/msg/Header'[] header + float32 thrust + float32 thrust_normalized + MissionUpdate + message + string drone_id + int32 mission_id + int32 item_id + uint8 action + string mission + ControllerInfo + message + 'std_msgs/msg/Header'[] header + 'as2_msgs/msg/ControlMode'[] input_control_mode + 'as2_msgs/msg/ControlMode'[] output_control_mode + BehaviorStatus + message + uint8 status + Geofence + message + int8 id + int8 alert + string type + 'geometry_msgs/msg/Polygon'[] polygon + NodeStatus + message + int8 status + TrajGenInfo + message + 'std_msgs/msg/Header'[] header + 'as2_msgs/msg/NodeStatus'[] node_status + uint8 active_status + PoseWithID + message + string id + 'geometry_msgs/msg/Pose'[] pose + MissionEvent + message + 'std_msgs/msg/Header'[] header + string data + PoseStampedWithID + message + string id + 'geometry_msgs/msg/PoseStamped'[] pose + Speed + message + 'std_msgs/msg/Header'[] header + float32 speed + FollowTargetInfo + message + 'std_msgs/msg/Header'[] header + int8 follow_status + int8 follow_mode + AlertEvent + message + int8 alert + string description + + srvs: + SetGeofence + request + response + 'as2_msgs/msg/Geofence'[] geofence + bool success + PackagePickUp + request + response + bool enable + 'geometry_msgs/msg/Twist'[] speed_limit + bool success + DynamicFollower + request + response + bool enable + 'geometry_msgs/msg/Twist'[] speed_limit + bool success + PathToGeopath + request + response + 'nav_msgs/msg/Path'[] path + bool success + 'geographic_msgs/msg/GeoPath'[] geo_path + SetOrigin + request + response + 'geographic_msgs/msg/GeoPoint'[] origin + bool success + GeopathToPath + request + response + 'geographic_msgs/msg/GeoPath'[] geo_path + bool success + 'nav_msgs/msg/Path'[] path + GetGeofence + request + response + bool success + 'as2_msgs/msg/Geofence'[] geofences + GetOrigin + request + response + bool success + 'geographic_msgs/msg/GeoPoint'[] origin + SetControlMode + request + response + 'as2_msgs/msg/ControlMode'[] control_mode + bool success + SetSpeed + request + response + 'as2_msgs/msg/Speed'[] speed + bool success + PackageUnPick + request + response + bool enable + 'geometry_msgs/msg/Twist'[] speed_limit + bool success + ListControlModes + request + response + string source + uint8[] control_modes + SetPlatformStateMachineEvent + request + response + 'as2_msgs/msg/PlatformStateMachineEvent'[] event + bool success + 'as2_msgs/msg/PlatformStatus'[] current_state + DynamicLand + request + response + bool enable + 'geometry_msgs/msg/Twist'[] speed_limit + bool success + + actions: + GoToWaypoint + goal + 'as2_msgs/msg/YawMode'[] yaw + 'geometry_msgs/msg/PointStamped'[] target_pose + float32 max_speed + result + bool go_to_success + feedback + float32 actual_speed + float32 actual_distance_to_goal + SetArmingState + goal + bool 'request' + result + bool success + feedback + FollowPath + goal + 'std_msgs/msg/Header'[] header + 'as2_msgs/msg/YawMode'[] yaw + 'as2_msgs/msg/PoseWithID'[] path + float32 max_speed + result + bool follow_path_success + feedback + float32 actual_speed + float32 actual_distance_to_next_waypoint + uint16 remaining_waypoints + string next_waypoint_id + GeneratePolynomialTrajectory + goal + 'std_msgs/msg/Header'[] header + 'as2_msgs/msg/YawMode'[] yaw + 'as2_msgs/msg/PoseWithID'[] path + float32 max_speed + result + bool trajectory_generator_success + feedback + string next_waypoint_id + uint16 remaining_waypoints + FollowReference + goal + 'as2_msgs/msg/YawMode'[] yaw + 'geometry_msgs/msg/PointStamped'[] target_pose + float32 max_speed_x + float32 max_speed_y + float32 max_speed_z + result + bool follow_reference_success + feedback + float32 actual_speed + float32 actual_distance_to_goal + SetOffboardMode + goal + bool 'request' + result + bool success + feedback + TakeOff + goal + float32 takeoff_height + float32 takeoff_speed + result + bool takeoff_success + feedback + float32 actual_takeoff_speed + float32 actual_takeoff_height + DetectArucoMarkers + goal + uint16[] target_ids + result + bool success + feedback + bool sucess + Land + goal + float32 land_speed + result + bool land_success + feedback + float32 actual_land_speed + float32 actual_land_height + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/bond.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/bond.ros new file mode 100644 index 0000000..054fcb6 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/bond.ros @@ -0,0 +1,15 @@ +bond: + msgs: + Status + message + 'std_msgs/msg/Header'[] header + string id + string instance_id + bool active + float32 heartbeat_timeout + float32 heartbeat_period + Constants + message + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/builtin_interfaces.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/builtin_interfaces.ros new file mode 100644 index 0000000..6a2a31d --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/builtin_interfaces.ros @@ -0,0 +1,13 @@ +builtin_interfaces: + msgs: + Time + message + int32 sec + uint32 nanosec + Duration + message + int32 sec + uint32 nanosec + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/cartographer_ros_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/cartographer_ros_msgs.ros new file mode 100644 index 0000000..f430e44 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/cartographer_ros_msgs.ros @@ -0,0 +1,119 @@ +cartographer_ros_msgs: + msgs: + LandmarkEntry + message + string id + 'geometry_msgs/msg/Pose'[] tracking_from_landmark_transform + float64 translation_weight + float64 rotation_weight + HistogramBucket + message + float64 bucket_boundary + float64 count + LandmarkList + message + 'std_msgs/msg/Header'[] header + 'cartographer_ros_msgs/msg/LandmarkEntry'[] landmarks + BagfileProgress + message + string current_bagfile_name + uint32 current_bagfile_id + uint32 total_bagfiles + uint32 total_messages + uint32 processed_messages + float32 total_seconds + float32 processed_seconds + MetricFamily + message + string name + string description + 'cartographer_ros_msgs/msg/Metric'[] metrics + TrajectoryStates + message + 'std_msgs/msg/Header'[] header + int32[] trajectory_id + uint8[] trajectory_state + SubmapTexture + message + uint8[] cells + int32 width + int32 height + float64 resolution + 'geometry_msgs/msg/Pose'[] slice_pose + Metric + message + uint8 type + 'cartographer_ros_msgs/msg/MetricLabel'[] labels + float64 value + 'cartographer_ros_msgs/msg/HistogramBucket'[] counts_by_bucket + StatusResponse + message + uint8 code + string message + StatusCode + message + SubmapEntry + message + int32 trajectory_id + int32 submap_index + int32 submap_version + 'geometry_msgs/msg/Pose'[] pose + bool is_frozen + SubmapList + message + 'std_msgs/msg/Header'[] header + 'cartographer_ros_msgs/msg/SubmapEntry'[] submap + MetricLabel + message + string key + string value + + srvs: + SubmapQuery + request + int32 trajectory_id + int32 submap_index + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + int32 submap_version + 'cartographer_ros_msgs/msg/SubmapTexture'[] textures + WriteState + request + string filename + bool include_unfinished_submaps + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + FinishTrajectory + request + int32 trajectory_id + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + TrajectoryQuery + request + int32 trajectory_id + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + 'geometry_msgs/msg/PoseStamped'[] trajectory + GetTrajectoryStates + request + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + 'cartographer_ros_msgs/msg/TrajectoryStates'[] trajectory_states + StartTrajectory + request + string configuration_directory + string configuration_basename + bool use_initial_pose + 'geometry_msgs/msg/Pose'[] initial_pose + int32 relative_to_trajectory_id + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + int32 trajectory_id + ReadMetrics + request + response + 'cartographer_ros_msgs/msg/StatusResponse'[] status + 'cartographer_ros_msgs/msg/MetricFamily'[] metric_families + 'builtin_interfaces/msg/Time'[] timestamp + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/cascade_lifecycle_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/cascade_lifecycle_msgs.ros new file mode 100644 index 0000000..b846481 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/cascade_lifecycle_msgs.ros @@ -0,0 +1,14 @@ +cascade_lifecycle_msgs: + msgs: + State + message + uint8 state + string node_name + Activation + message + uint8 operation_type + string activator + string activation + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/color_pose_estimation_skill.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/color_pose_estimation_skill.ros new file mode 100644 index 0000000..c79a3c5 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/color_pose_estimation_skill.ros @@ -0,0 +1,16 @@ +color_pose_estimation_skill: + + + actions: + ColorPoseEstimation + goal + string color + string sub_topic_name + int16 timeout + string element + result + uint16 error_code_id + 'geometry_msgs/msg/PoseStamped'[] color_pose_cube_holder + 'geometry_msgs/msg/PoseStamped'[] color_pose_cube + feedback + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/color_pose_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/color_pose_msgs.ros new file mode 100644 index 0000000..44597ee --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/color_pose_msgs.ros @@ -0,0 +1,15 @@ +color_pose_msgs: + msgs: + ColorPoseArray + message + 'std_msgs/msg/Header'[] header + 'color_pose_msgs/msg/ColorPose'[] color_poses + ColorPose + message + 'std_msgs/msg/Header'[] header + string color + string element + 'geometry_msgs/msg/Pose'[] pose + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/control_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/control_msgs.ros new file mode 100644 index 0000000..2a6f66c --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/control_msgs.ros @@ -0,0 +1,191 @@ +control_msgs: + msgs: + DynamicJointState + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'control_msgs/msg/InterfaceValue'[] interface_values + AdmittanceControllerState + message + 'std_msgs/msg/Float64MultiArray'[] mass + 'std_msgs/msg/Float64MultiArray'[] damping + 'std_msgs/msg/Float64MultiArray'[] stiffness + 'geometry_msgs/msg/Quaternion'[] rot_base_control + 'geometry_msgs/msg/TransformStamped'[] ref_trans_base_ft + 'std_msgs/msg/Int8MultiArray'[] selected_axes + 'std_msgs/msg/String'[] ft_sensor_frame + 'geometry_msgs/msg/TransformStamped'[] admittance_position + 'geometry_msgs/msg/TwistStamped'[] admittance_acceleration + 'geometry_msgs/msg/TwistStamped'[] admittance_velocity + 'geometry_msgs/msg/WrenchStamped'[] wrench_base + 'sensor_msgs/msg/JointState'[] joint_state + JointComponentTolerance + message + string joint_name + uint16 component + float64 position + float64 velocity + float64 acceleration + JointControllerState + message + 'std_msgs/msg/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 + InterfaceValue + message + string[] interface_names + float64[] values + PidState + message + 'std_msgs/msg/Header'[] header + 'builtin_interfaces/msg/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 + GripperCommand + message + float64 position + float64 max_effort + JointJog + message + 'std_msgs/msg/Header'[] header + string[] joint_names + float64[] displacements + float64[] velocities + float64 duration + MecanumDriveControllerState + message + 'std_msgs/msg/Header'[] header + float64 front_left_wheel_velocity + float64 back_left_wheel_velocity + float64 back_right_wheel_velocity + float64 front_right_wheel_velocity + 'geometry_msgs/msg/Twist'[] reference_velocity + JointTrajectoryControllerState + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'trajectory_msgs/msg/JointTrajectoryPoint'[] reference + 'trajectory_msgs/msg/JointTrajectoryPoint'[] feedback + 'trajectory_msgs/msg/JointTrajectoryPoint'[] error + 'trajectory_msgs/msg/JointTrajectoryPoint'[] output + 'trajectory_msgs/msg/JointTrajectoryPoint'[] desired + 'trajectory_msgs/msg/JointTrajectoryPoint'[] actual + string[] multi_dof_joint_names + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_reference + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_feedback + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_error + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_output + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_desired + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_actual + SteeringControllerStatus + message + 'std_msgs/msg/Header'[] header + float64[] traction_wheels_position + float64[] traction_wheels_velocity + float64[] steer_positions + float64[] linear_velocity_command + float64[] steering_angle_command + JointTolerance + message + string name + float64 position + float64 velocity + float64 acceleration + + srvs: + QueryTrajectoryState + request + 'builtin_interfaces/msg/Time'[] time + response + bool success + string message + string[] name + float64[] position + float64[] velocity + float64[] acceleration + QueryCalibrationState + request + response + bool is_calibrated + + actions: + JointTrajectory + goal + 'trajectory_msgs/msg/JointTrajectory'[] trajectory + result + feedback + GripperCommandAct + goal + 'control_msgs/msg/GripperCommand'[] command + result + float64 position + float64 effort + bool stalled + bool reached_goal + feedback + float64 position + float64 effort + bool stalled + bool reached_goal + PointHead + goal + 'geometry_msgs/msg/PointStamped'[] target + 'geometry_msgs/msg/Vector3'[] pointing_axis + string pointing_frame + 'builtin_interfaces/msg/Duration'[] min_duration + float64 max_velocity + result + feedback + float64 pointing_angle_error + FollowJointTrajectory + goal + 'trajectory_msgs/msg/JointTrajectory'[] trajectory + 'trajectory_msgs/msg/MultiDOFJointTrajectory'[] multi_dof_trajectory + 'control_msgs/msg/JointTolerance'[] path_tolerance + 'control_msgs/msg/JointComponentTolerance'[] component_path_tolerance + 'control_msgs/msg/JointTolerance'[] goal_tolerance + 'control_msgs/msg/JointComponentTolerance'[] component_goal_tolerance + 'builtin_interfaces/msg/Duration'[] goal_time_tolerance + result + int32 error_code + string error_string + feedback + 'std_msgs/msg/Header'[] header + string[] joint_names + 'trajectory_msgs/msg/JointTrajectoryPoint'[] desired + 'trajectory_msgs/msg/JointTrajectoryPoint'[] actual + 'trajectory_msgs/msg/JointTrajectoryPoint'[] error + string[] multi_dof_joint_names + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_desired + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_actual + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] multi_dof_error + SingleJointPosition + goal + float64 position + 'builtin_interfaces/msg/Duration'[] min_duration + float64 max_velocity + result + feedback + 'std_msgs/msg/Header'[] header + float64 position + float64 velocity + float64 error + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/controller_manager_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/controller_manager_msgs.ros new file mode 100644 index 0000000..7c06b25 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/controller_manager_msgs.ros @@ -0,0 +1,92 @@ +controller_manager_msgs: + msgs: + ControllerState + message + string name + string state + string type + string[] claimed_interfaces + string[] required_command_interfaces + string[] required_state_interfaces + bool is_chainable + bool is_chained + string[] reference_interfaces + 'controller_manager_msgs/msg/ChainConnection'[] chain_connections + ChainConnection + message + string name + string[] reference_interfaces + HardwareComponentState + message + string name + string type + string class_type + 'lifecycle_msgs/msg/State'[] state + 'controller_manager_msgs/msg/HardwareInterface'[] command_interfaces + 'controller_manager_msgs/msg/HardwareInterface'[] state_interfaces + HardwareInterface + message + string name + bool is_available + bool is_claimed + + srvs: + ListControllerTypes + request + response + string[] types + string[] base_classes + SwitchController + request + string[] activate_controllers + string[] deactivate_controllers + string[] start_controllers + string[] stop_controllers + int32 strictness + bool start_asap + bool activate_asap + 'builtin_interfaces/msg/Duration'[] timeout + response + bool ok + ListHardwareComponents + request + response + 'controller_manager_msgs/msg/HardwareComponentState'[] component + SetHardwareComponentState + request + string name + 'lifecycle_msgs/msg/State'[] target_state + response + bool ok + 'lifecycle_msgs/msg/State'[] state + LoadController + request + string name + response + bool ok + UnloadController + request + string name + response + bool ok + ReloadControllerLibraries + request + bool force_kill + response + bool ok + ListControllers + request + response + 'controller_manager_msgs/msg/ControllerState'[] controller + ListHardwareInterfaces + request + response + 'controller_manager_msgs/msg/HardwareInterface'[] command_interfaces + 'controller_manager_msgs/msg/HardwareInterface'[] state_interfaces + ConfigureController + request + string name + response + bool ok + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/detect_aruco_marker_skill.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/detect_aruco_marker_skill.ros new file mode 100644 index 0000000..afb4d6a --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/detect_aruco_marker_skill.ros @@ -0,0 +1,15 @@ +detect_aruco_marker_skill: + + + actions: + ArucoMarkerDetection + goal + int16 marker_id + int16 timeout + string sub_topic_name + int8 required_pose_num + result + uint16 error_code_id + 'geometry_msgs/msg/PoseStamped'[] pose + feedback + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/diagnostic_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/diagnostic_msgs.ros new file mode 100644 index 0000000..0934098 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/diagnostic_msgs.ros @@ -0,0 +1,33 @@ +diagnostic_msgs: + msgs: + DiagnosticStatus + message + byte level + string name + string message + string hardware_id + 'diagnostic_msgs/msg/KeyValue'[] values + DiagnosticArray + message + 'std_msgs/msg/Header'[] header + 'diagnostic_msgs/msg/DiagnosticStatus'[] status + KeyValue + message + string key + string value + + srvs: + AddDiagnostics + request + string load_namespace + response + bool success + string message + SelfTest + request + response + string id + byte passed + 'diagnostic_msgs/msg/DiagnosticStatus'[] status + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/dwb_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/dwb_msgs.ros new file mode 100644 index 0000000..cb05e6d --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/dwb_msgs.ros @@ -0,0 +1,63 @@ +dwb_msgs: + msgs: + CriticScore + message + string name + float32 raw_score + float32 scale + LocalPlanEvaluation + message + 'std_msgs/msg/Header'[] header + 'dwb_msgs/msg/TrajectoryScore'[] twists + uint16 best_index + uint16 worst_index + TrajectoryScore + message + 'dwb_msgs/msg/Trajectory2D'[] traj + 'dwb_msgs/msg/CriticScore'[] scores + float32 total + Trajectory2D + message + 'nav_2d_msgs/msg/Twist2D'[] velocity + 'builtin_interfaces/msg/Duration'[] time_offsets + 'geometry_msgs/msg/Pose2D'[] poses + + srvs: + DebugLocalPlan + request + 'nav_2d_msgs/msg/Pose2DStamped'[] pose + 'nav_2d_msgs/msg/Twist2D'[] velocity + 'nav_2d_msgs/msg/Path2D'[] global_plan + response + 'dwb_msgs/msg/LocalPlanEvaluation'[] results + GenerateTwists + request + 'nav_2d_msgs/msg/Twist2D'[] current_vel + response + 'nav_2d_msgs/msg/Twist2D'[] twists + GetCriticScore + request + 'nav_2d_msgs/msg/Pose2DStamped'[] pose + 'nav_2d_msgs/msg/Twist2D'[] velocity + 'nav_2d_msgs/msg/Path2D'[] global_plan + 'dwb_msgs/msg/Trajectory2D'[] traj + string critic_name + response + 'dwb_msgs/msg/CriticScore'[] score + ScoreTrajectory + request + 'nav_2d_msgs/msg/Pose2DStamped'[] pose + 'nav_2d_msgs/msg/Twist2D'[] velocity + 'nav_2d_msgs/msg/Path2D'[] global_plan + 'dwb_msgs/msg/Trajectory2D'[] traj + response + 'dwb_msgs/msg/TrajectoryScore'[] score + GenerateTrajectory + request + 'geometry_msgs/msg/Pose2D'[] start_pose + 'nav_2d_msgs/msg/Twist2D'[] start_vel + 'nav_2d_msgs/msg/Twist2D'[] cmd_vel + response + 'dwb_msgs/msg/Trajectory2D'[] traj + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/geographic_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/geographic_msgs.ros new file mode 100644 index 0000000..93b5475 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/geographic_msgs.ros @@ -0,0 +1,121 @@ +geographic_msgs: + msgs: + GeoPointStamped + message + 'std_msgs/msg/Header'[] header + 'geographic_msgs/msg/GeoPoint'[] position + GeoPoint + message + float64 latitude + float64 longitude + float64 altitude + GeoPoseWithCovariance + message + 'geographic_msgs/msg/GeoPose'[] pose + float64[] covariance + GeoPath + message + 'std_msgs/msg/Header'[] header + 'geographic_msgs/msg/GeoPoseStamped'[] poses + GeoPoseStamped + message + 'std_msgs/msg/Header'[] header + 'geographic_msgs/msg/GeoPose'[] pose + WayPoint + message + 'unique_identifier_msgs/msg/UUID'[] id + 'geographic_msgs/msg/GeoPoint'[] position + 'geographic_msgs/msg/KeyValue'[] props + GeoPoseWithCovarianceStamped + message + 'std_msgs/msg/Header'[] header + 'geographic_msgs/msg/GeoPoseWithCovariance'[] pose + BoundingBox + message + 'geographic_msgs/msg/GeoPoint'[] min_pt + 'geographic_msgs/msg/GeoPoint'[] max_pt + GeographicMapChanges + message + 'std_msgs/msg/Header'[] header + 'geographic_msgs/msg/GeographicMap'[] diffs + 'unique_identifier_msgs/msg/UUID'[] deletes + MapFeature + message + 'unique_identifier_msgs/msg/UUID'[] id + 'unique_identifier_msgs/msg/UUID'[] components + 'geographic_msgs/msg/KeyValue'[] props + RoutePath + message + 'std_msgs/msg/Header'[] header + 'unique_identifier_msgs/msg/UUID'[] network + 'unique_identifier_msgs/msg/UUID'[] segments + 'geographic_msgs/msg/KeyValue'[] props + RouteNetwork + message + 'std_msgs/msg/Header'[] header + 'unique_identifier_msgs/msg/UUID'[] id + 'geographic_msgs/msg/BoundingBox'[] bounds + 'geographic_msgs/msg/WayPoint'[] points + 'geographic_msgs/msg/RouteSegment'[] segments + 'geographic_msgs/msg/KeyValue'[] props + RouteSegment + message + 'unique_identifier_msgs/msg/UUID'[] id + 'unique_identifier_msgs/msg/UUID'[] start + 'unique_identifier_msgs/msg/UUID'[] end + 'geographic_msgs/msg/KeyValue'[] props + GeographicMap + message + 'std_msgs/msg/Header'[] header + 'unique_identifier_msgs/msg/UUID'[] id + 'geographic_msgs/msg/BoundingBox'[] bounds + 'geographic_msgs/msg/WayPoint'[] points + 'geographic_msgs/msg/MapFeature'[] features + 'geographic_msgs/msg/KeyValue'[] props + KeyValue + message + string key + string value + GeoPose + message + 'geographic_msgs/msg/GeoPoint'[] position + 'geometry_msgs/msg/Quaternion'[] orientation + + srvs: + UpdateGeographicMap + request + 'geographic_msgs/msg/GeographicMapChanges'[] updates + response + bool success + string status + GetRoutePlan + request + 'unique_identifier_msgs/msg/UUID'[] network + 'unique_identifier_msgs/msg/UUID'[] start + 'unique_identifier_msgs/msg/UUID'[] goal + response + bool success + string status + 'geographic_msgs/msg/RoutePath'[] plan + GetGeographicMap + request + string url + 'geographic_msgs/msg/BoundingBox'[] bounds + response + bool success + string status + 'geographic_msgs/msg/GeographicMap'[] map + GetGeoPath + request + 'geographic_msgs/msg/GeoPoint'[] start + 'geographic_msgs/msg/GeoPoint'[] goal + response + bool success + string status + 'geographic_msgs/msg/GeoPath'[] plan + 'unique_identifier_msgs/msg/UUID'[] network + 'unique_identifier_msgs/msg/UUID'[] start_seg + 'unique_identifier_msgs/msg/UUID'[] goal_seg + float64 distance + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/io_control_gripper_skill.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/io_control_gripper_skill.ros new file mode 100644 index 0000000..a115296 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/io_control_gripper_skill.ros @@ -0,0 +1,14 @@ +io_control_gripper_skill: + + + actions: + IOGripperCommand + goal + string io_service_server_name + bool open + int16 timeout + result + uint16 error_code_id + feedback + bool open + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/lifecycle_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/lifecycle_msgs.ros new file mode 100644 index 0000000..a92d006 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/lifecycle_msgs.ros @@ -0,0 +1,42 @@ +lifecycle_msgs: + msgs: + TransitionDescription + message + 'lifecycle_msgs/msg/Transition'[] transition + 'lifecycle_msgs/msg/State'[] start_state + 'lifecycle_msgs/msg/State'[] goal_state + Transition + message + uint8 id + string label + TransitionEvent + message + uint64 timestamp + 'lifecycle_msgs/msg/Transition'[] transition + 'lifecycle_msgs/msg/State'[] start_state + 'lifecycle_msgs/msg/State'[] goal_state + State + message + uint8 id + string label + + srvs: + ChangeState + request + 'lifecycle_msgs/msg/Transition'[] transition + response + bool success + GetState + request + response + 'lifecycle_msgs/msg/State'[] current_state + GetAvailableTransitions + request + response + 'lifecycle_msgs/msg/TransitionDescription'[] available_transitions + GetAvailableStates + request + response + 'lifecycle_msgs/msg/State'[] available_states + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/logging_demo.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/logging_demo.ros new file mode 100644 index 0000000..f489a8a --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/logging_demo.ros @@ -0,0 +1,11 @@ +logging_demo: + + srvs: + ConfigLogger + request + string logger_name + string level + response + bool success + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/man2_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/man2_msgs.ros new file mode 100644 index 0000000..ee6f593 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/man2_msgs.ros @@ -0,0 +1,17 @@ +man2_msgs: + + + actions: + RunApplication + goal + string behavior_tree_filename + string behavior_tree_xml + bool run_in_loop + int16 sleep + result + bool success + feedback + float64 percentage + 'builtin_interfaces/msg/Duration'[] execution_time + int16 number_of_recoveries + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/map_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/map_msgs.ros new file mode 100644 index 0000000..db589b5 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/map_msgs.ros @@ -0,0 +1,64 @@ +map_msgs: + msgs: + ProjectedMap + message + 'nav_msgs/msg/OccupancyGrid'[] map + float64 min_z + float64 max_z + PointCloud2Update + message + 'std_msgs/msg/Header'[] header + uint32 type + 'sensor_msgs/msg/PointCloud2'[] points + OccupancyGridUpdate + message + 'std_msgs/msg/Header'[] header + int32 x + int32 y + uint32 width + uint32 height + int8[] data + ProjectedMapInfo + message + string frame_id + float64 x + float64 y + float64 width + float64 height + float64 min_z + float64 max_z + + srvs: + GetPointMapROI + request + float64 x + float64 y + float64 z + response + 'sensor_msgs/msg/PointCloud2'[] sub_map + ProjectedMapsInfo + request + 'map_msgs/msg/ProjectedMapInfo'[] projected_maps_info + response + GetPointMap + request + response + 'sensor_msgs/msg/PointCloud2'[] map + SaveMap + request + 'std_msgs/msg/String'[] filename + response + SetMapProjections + request + response + 'map_msgs/msg/ProjectedMapInfo'[] projected_maps_info + GetMapROI + request + float64 x + float64 y + float64 l_x + float64 l_y + response + 'nav_msgs/msg/OccupancyGrid'[] sub_map + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav2_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav2_msgs.ros new file mode 100644 index 0000000..7721de6 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav2_msgs.ros @@ -0,0 +1,226 @@ +nav2_msgs: + msgs: + BehaviorTreeStatusChange + message + 'builtin_interfaces/msg/Time'[] timestamp + string node_name + string previous_status + string current_status + CostmapMetaData + message + 'builtin_interfaces/msg/Time'[] map_load_time + 'builtin_interfaces/msg/Time'[] update_time + string layer + float32 resolution + uint32 size_x + uint32 size_y + 'geometry_msgs/msg/Pose'[] origin + Costmap + message + 'std_msgs/msg/Header'[] header + 'nav2_msgs/msg/CostmapMetaData'[] metadata + uint8[] data + VoxelGrid + message + 'std_msgs/msg/Header'[] header + uint32[] data + 'geometry_msgs/msg/Point32'[] origin + 'geometry_msgs/msg/Vector3'[] resolutions + uint32 size_x + uint32 size_y + uint32 size_z + Particle + message + 'geometry_msgs/msg/Pose'[] pose + float64 weight + SpeedLimit + message + 'std_msgs/msg/Header'[] header + bool percentage + float64 speed_limit + BehaviorTreeLog + message + 'builtin_interfaces/msg/Time'[] timestamp + 'nav2_msgs/msg/BehaviorTreeStatusChange'[] event_log + ParticleCloud + message + 'std_msgs/msg/Header'[] header + 'nav2_msgs/msg/Particle'[] particles + CostmapFilterInfo + message + 'std_msgs/msg/Header'[] header + uint8 type + string filter_mask_topic + float32 base + float32 multiplier + + srvs: + ClearEntireCostmap + request + 'std_msgs/msg/Empty'[] 'request' + response + 'std_msgs/msg/Empty'[] 'response' + ClearCostmapAroundRobot + request + float32 reset_distance + response + 'std_msgs/msg/Empty'[] 'response' + GetCostmap + request + 'nav2_msgs/msg/CostmapMetaData'[] specs + response + 'nav2_msgs/msg/Costmap'[] map + ManageLifecycleNodes + request + uint8 command + response + bool success + LoadMap + request + string map_url + response + 'nav_msgs/msg/OccupancyGrid'[] map + uint8 result + ClearCostmapExceptRegion + request + float32 reset_distance + response + 'std_msgs/msg/Empty'[] 'response' + SaveMap + request + string map_topic + string map_url + string image_format + string map_mode + float32 free_thresh + float32 occupied_thresh + response + bool result + IsPathValid + request + 'nav_msgs/msg/Path'[] path + response + bool is_valid + int32[] invalid_pose_indices + + actions: + FollowPath + goal + 'nav_msgs/msg/Path'[] path + string controller_id + string goal_checker_id + result + 'std_msgs/msg/Empty'[] result + feedback + float32 distance_to_goal + float32 speed + NavigateThroughPoses + goal + 'geometry_msgs/msg/PoseStamped'[] poses + string behavior_tree + result + 'std_msgs/msg/Empty'[] result + feedback + 'geometry_msgs/msg/PoseStamped'[] current_pose + 'builtin_interfaces/msg/Duration'[] navigation_time + 'builtin_interfaces/msg/Duration'[] estimated_time_remaining + int16 number_of_recoveries + float32 distance_remaining + int16 number_of_poses_remaining + ComputePathThroughPoses + goal + 'geometry_msgs/msg/PoseStamped'[] goals + 'geometry_msgs/msg/PoseStamped'[] start + string planner_id + bool use_start + result + 'nav_msgs/msg/Path'[] path + 'builtin_interfaces/msg/Duration'[] planning_time + feedback + AssistedTeleop + goal + 'builtin_interfaces/msg/Duration'[] time_allowance + result + 'builtin_interfaces/msg/Duration'[] total_elapsed_time + feedback + 'builtin_interfaces/msg/Duration'[] current_teleop_duration + Spin + goal + float32 target_yaw + 'builtin_interfaces/msg/Duration'[] time_allowance + result + 'builtin_interfaces/msg/Duration'[] total_elapsed_time + feedback + float32 angular_distance_traveled + ComputePathToPose + goal + 'geometry_msgs/msg/PoseStamped'[] goal + 'geometry_msgs/msg/PoseStamped'[] start + string planner_id + bool use_start + result + 'nav_msgs/msg/Path'[] path + 'builtin_interfaces/msg/Duration'[] planning_time + feedback + DummyBehavior + goal + 'std_msgs/msg/String'[] command + result + 'builtin_interfaces/msg/Duration'[] total_elapsed_time + feedback + SmoothPath + goal + 'nav_msgs/msg/Path'[] path + string smoother_id + 'builtin_interfaces/msg/Duration'[] max_smoothing_duration + bool check_for_collisions + result + 'nav_msgs/msg/Path'[] path + 'builtin_interfaces/msg/Duration'[] smoothing_duration + bool was_completed + feedback + DriveOnHeading + goal + 'geometry_msgs/msg/Point'[] target + float32 speed + 'builtin_interfaces/msg/Duration'[] time_allowance + result + 'builtin_interfaces/msg/Duration'[] total_elapsed_time + feedback + float32 distance_traveled + NavigateToPose + goal + 'geometry_msgs/msg/PoseStamped'[] pose + string behavior_tree + result + 'std_msgs/msg/Empty'[] result + feedback + 'geometry_msgs/msg/PoseStamped'[] current_pose + 'builtin_interfaces/msg/Duration'[] navigation_time + 'builtin_interfaces/msg/Duration'[] estimated_time_remaining + int16 number_of_recoveries + float32 distance_remaining + BackUp + goal + 'geometry_msgs/msg/Point'[] target + float32 speed + 'builtin_interfaces/msg/Duration'[] time_allowance + result + 'builtin_interfaces/msg/Duration'[] total_elapsed_time + feedback + float32 distance_traveled + Wait + goal + 'builtin_interfaces/msg/Duration'[] time + result + 'builtin_interfaces/msg/Duration'[] total_elapsed_time + feedback + 'builtin_interfaces/msg/Duration'[] time_left + FollowWaypoints + goal + 'geometry_msgs/msg/PoseStamped'[] poses + result + int32[] missed_waypoints + feedback + uint32 current_waypoint + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav_2d_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav_2d_msgs.ros new file mode 100644 index 0000000..2e8aeb7 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav_2d_msgs.ros @@ -0,0 +1,32 @@ +nav_2d_msgs: + msgs: + Path2D + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose2D'[] poses + Twist2D + message + float64 x + float64 y + float64 theta + Pose2D32 + message + float32 x + float32 y + float32 theta + Pose2DStamped + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose2D'[] pose + Twist2D32 + message + float32 x + float32 y + float32 theta + Twist2DStamped + message + 'std_msgs/msg/Header'[] header + 'nav_2d_msgs/msg/Twist2D'[] velocity + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav_msgs.ros new file mode 100644 index 0000000..ee9fa85 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/nav_msgs.ros @@ -0,0 +1,57 @@ +nav_msgs: + msgs: + Path + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/PoseStamped'[] poses + OccupancyGrid + message + 'std_msgs/msg/Header'[] header + 'nav_msgs/msg/MapMetaData'[] info + int8[] data + Odometry + message + 'std_msgs/msg/Header'[] header + string child_frame_id + 'geometry_msgs/msg/PoseWithCovariance'[] pose + 'geometry_msgs/msg/TwistWithCovariance'[] twist + GridCells + message + 'std_msgs/msg/Header'[] header + float32 cell_width + float32 cell_height + 'geometry_msgs/msg/Point'[] cells + MapMetaData + message + 'builtin_interfaces/msg/Time'[] map_load_time + float32 resolution + uint32 width + uint32 height + 'geometry_msgs/msg/Pose'[] origin + + srvs: + SetMap + request + 'nav_msgs/msg/OccupancyGrid'[] map + 'geometry_msgs/msg/PoseWithCovarianceStamped'[] initial_pose + response + bool success + LoadMap + request + string map_url + response + 'nav_msgs/msg/OccupancyGrid'[] map + uint8 result + GetPlan + request + 'geometry_msgs/msg/PoseStamped'[] start + 'geometry_msgs/msg/PoseStamped'[] goal + float32 tolerance + response + 'nav_msgs/msg/Path'[] plan + GetMap + request + response + 'nav_msgs/msg/OccupancyGrid'[] map + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/object_recognition_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/object_recognition_msgs.ros new file mode 100644 index 0000000..2854553 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/object_recognition_msgs.ros @@ -0,0 +1,51 @@ +object_recognition_msgs: + msgs: + ObjectInformation + message + string name + 'shape_msgs/msg/Mesh'[] ground_truth_mesh + 'sensor_msgs/msg/PointCloud2'[] ground_truth_point_cloud + Table + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose'[] pose + 'geometry_msgs/msg/Point'[] convex_hull + RecognizedObject + message + 'std_msgs/msg/Header'[] header + 'object_recognition_msgs/msg/ObjectType'[] type + float32 confidence + 'sensor_msgs/msg/PointCloud2'[] point_clouds + 'shape_msgs/msg/Mesh'[] bounding_mesh + 'geometry_msgs/msg/Point'[] bounding_contours + 'geometry_msgs/msg/PoseWithCovarianceStamped'[] pose + TableArray + message + 'std_msgs/msg/Header'[] header + 'object_recognition_msgs/msg/Table'[] tables + RecognizedObjectArray + message + 'std_msgs/msg/Header'[] header + 'object_recognition_msgs/msg/RecognizedObject'[] objects + float32[] cooccurrence + ObjectType + message + string key + string db + + srvs: + GetObjectInformation + request + 'object_recognition_msgs/msg/ObjectType'[] type + response + 'object_recognition_msgs/msg/ObjectInformation'[] information + + actions: + ObjectRecognition + goal + bool use_roi + float32[] filter_limits + result + 'object_recognition_msgs/msg/RecognizedObjectArray'[] recognized_objects + feedback + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/octomap_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/octomap_msgs.ros new file mode 100644 index 0000000..ddb02ac --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/octomap_msgs.ros @@ -0,0 +1,27 @@ +octomap_msgs: + msgs: + OctomapWithPose + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose'[] origin + 'octomap_msgs/msg/Octomap'[] octomap + Octomap + message + 'std_msgs/msg/Header'[] header + bool binary + string id + float64 resolution + int8[] data + + srvs: + GetOctomap + request + response + 'octomap_msgs/msg/Octomap'[] map + BoundingBoxQuery + request + 'geometry_msgs/msg/Point'[] min + 'geometry_msgs/msg/Point'[] max + response + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/pcl_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/pcl_msgs.ros new file mode 100644 index 0000000..e380692 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/pcl_msgs.ros @@ -0,0 +1,27 @@ +pcl_msgs: + msgs: + ModelCoefficients + message + 'std_msgs/msg/Header'[] header + float32[] values + PointIndices + message + 'std_msgs/msg/Header'[] header + int32[] indices + Vertices + message + uint32[] vertices + PolygonMesh + message + 'std_msgs/msg/Header'[] header + 'sensor_msgs/msg/PointCloud2'[] cloud + 'pcl_msgs/msg/Vertices'[] polygons + + srvs: + UpdateFilename + request + string filename + response + bool success + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/pendulum_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/pendulum_msgs.ros new file mode 100644 index 0000000..52faa7a --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/pendulum_msgs.ros @@ -0,0 +1,24 @@ +pendulum_msgs: + msgs: + JointCommand + message + float64 position + RttestResults + message + 'builtin_interfaces/msg/Time'[] stamp + 'pendulum_msgs/msg/JointCommand'[] command + 'pendulum_msgs/msg/JointState'[] state + uint64 cur_latency + float64 mean_latency + uint64 min_latency + uint64 max_latency + uint64 minor_pagefaults + uint64 major_pagefaults + JointState + message + float64 position + float64 velocity + float64 effort + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/phidgets_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/phidgets_msgs.ros new file mode 100644 index 0000000..4fd08aa --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/phidgets_msgs.ros @@ -0,0 +1,22 @@ +phidgets_msgs: + msgs: + EncoderDecimatedSpeed + message + 'std_msgs/msg/Header'[] header + float64 avr_speed + + srvs: + SetDigitalOutput + request + uint16 index + bool state + response + bool success + SetAnalogOutput + request + uint16 index + float64 voltage + response + bool success + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/plansys2_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/plansys2_msgs.ros new file mode 100644 index 0000000..8ed6fee --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/plansys2_msgs.ros @@ -0,0 +1,246 @@ +plansys2_msgs: + msgs: + DurativeAction + message + string name + 'plansys2_msgs/msg/Param'[] parameters + 'plansys2_msgs/msg/Tree'[] at_start_requirements + 'plansys2_msgs/msg/Tree'[] over_all_requirements + 'plansys2_msgs/msg/Tree'[] at_end_requirements + 'plansys2_msgs/msg/Tree'[] at_start_effects + 'plansys2_msgs/msg/Tree'[] at_end_effects + Tree + message + 'plansys2_msgs/msg/Node'[] nodes + ActionExecution + message + int16 type + string node_id + string action + string[] arguments + bool success + float32 completion + string status + Plan + message + 'plansys2_msgs/msg/PlanItem'[] items + ActionPerformerStatus + message + 'builtin_interfaces/msg/Time'[] status_stamp + int8 state + string action + string[] specialized_arguments + string node_name + Action + message + string name + 'plansys2_msgs/msg/Param'[] parameters + 'plansys2_msgs/msg/Tree'[] preconditions + 'plansys2_msgs/msg/Tree'[] effects + PlanItem + message + float32 time + string action + float32 duration + Param + message + string name + string type + string[] sub_types + Node + message + uint8 node_type + uint8 expression_type + uint8 modifier_type + uint32 node_id + uint32[] children + string name + 'plansys2_msgs/msg/Param'[] parameters + float64 value + bool negate + Knowledge + message + string[] instances + string[] predicates + string[] functions + string goal + ActionExecutionInfo + message + int8 status + 'builtin_interfaces/msg/Time'[] start_stamp + 'builtin_interfaces/msg/Time'[] status_stamp + string action_full_name + string action + string[] arguments + 'builtin_interfaces/msg/Duration'[] duration + float32 completion + string message_status + + srvs: + GetProblem + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string problem + string error_info + GetDomainDurativeActionDetails + request + string durative_action + string[] parameters + response + bool success + 'plansys2_msgs/msg/DurativeAction'[] durative_action + string error_info + GetProblemGoal + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + 'plansys2_msgs/msg/Tree'[] tree + string error_info + AffectParam + request + 'plansys2_msgs/msg/Param'[] param + response + bool success + string error_info + IsProblemGoalSatisfied + request + 'plansys2_msgs/msg/Tree'[] tree + response + bool success + bool satisfied + string error_info + GetOrderedSubGoals + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + 'plansys2_msgs/msg/Tree'[] sub_goals + string error_info + AddProblem + request + string problem + response + bool success + string error_info + GetProblemInstances + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + 'plansys2_msgs/msg/Param'[] instances + string error_info + AddProblemGoal + request + 'plansys2_msgs/msg/Tree'[] tree + response + bool success + string error_info + GetDomain + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string domain + string error_info + GetPlan + request + string domain + string problem + response + bool success + 'plansys2_msgs/msg/Plan'[] plan + string error_info + GetProblemInstanceDetails + request + string instance + response + bool success + 'plansys2_msgs/msg/Param'[] instance + string error_info + ExistNode + request + 'plansys2_msgs/msg/Node'[] 'node' + response + bool exist + GetDomainActionDetails + request + string action + string[] parameters + response + 'plansys2_msgs/msg/Action'[] action + bool success + string error_info + RemoveProblemGoal + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string error_info + GetDomainName + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string name + string error_info + ClearProblemKnowledge + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string error_info + GetDomainConstants + request + string type + response + bool success + string[] constants + string error_info + GetDomainTypes + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string[] types + string error_info + GetNodeDetails + request + string expression + response + bool success + 'plansys2_msgs/msg/Node'[] 'node' + string error_info + AffectNode + request + 'plansys2_msgs/msg/Node'[] 'node' + response + bool success + string error_info + GetStates + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + 'plansys2_msgs/msg/Node'[] states + string error_info + GetDomainActions + request + 'std_msgs/msg/Empty'[] 'request' + response + bool success + string[] actions + string error_info + + actions: + ExecutePlan + goal + 'plansys2_msgs/msg/Plan'[] plan + result + bool success + 'plansys2_msgs/msg/ActionExecutionInfo'[] action_execution_status + feedback + 'plansys2_msgs/msg/ActionExecutionInfo'[] action_execution_status + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rcl_interfaces.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rcl_interfaces.ros new file mode 100644 index 0000000..b6dbc88 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rcl_interfaces.ros @@ -0,0 +1,102 @@ +rcl_interfaces: + msgs: + ParameterDescriptor + message + string name + uint8 type + string description + string additional_constraints + bool read_only + bool dynamic_typing + ListParametersResult + message + string[] names + string[] prefixes + ParameterEventDescriptors + message + 'rcl_interfaces/msg/ParameterDescriptor'[] new_parameters + 'rcl_interfaces/msg/ParameterDescriptor'[] changed_parameters + 'rcl_interfaces/msg/ParameterDescriptor'[] deleted_parameters + Parameter + message + string name + 'rcl_interfaces/msg/ParameterValue'[] value + ParameterValue + message + uint8 type + bool bool_value + int64 integer_value + float64 double_value + string string_value + byte[] byte_array_value + bool[] bool_array_value + int64[] integer_array_value + float64[] double_array_value + string[] string_array_value + IntegerRange + message + int64 from_value + int64 to_value + uint64 step + ParameterEvent + message + 'builtin_interfaces/msg/Time'[] stamp + string 'node' + 'rcl_interfaces/msg/Parameter'[] new_parameters + 'rcl_interfaces/msg/Parameter'[] changed_parameters + 'rcl_interfaces/msg/Parameter'[] deleted_parameters + SetParametersResult + message + bool successful + string reason + FloatingPointRange + message + float64 from_value + float64 to_value + float64 step + Log + message + 'builtin_interfaces/msg/Time'[] stamp + uint8 level + string name + string msg + string file + string function + uint32 line + ParameterType + message + + srvs: + GetParameterTypes + request + string[] names + response + uint8[] types + DescribeParameters + request + string[] names + response + 'rcl_interfaces/msg/ParameterDescriptor'[] descriptors + SetParametersAtomically + request + 'rcl_interfaces/msg/Parameter'[] parameters + response + 'rcl_interfaces/msg/SetParametersResult'[] result + SetParameters + request + 'rcl_interfaces/msg/Parameter'[] parameters + response + 'rcl_interfaces/msg/SetParametersResult'[] results + GetParameters + request + string[] names + response + 'rcl_interfaces/msg/ParameterValue'[] values + ListParameters + request + string[] prefixes + uint64 depth + response + 'rcl_interfaces/msg/ListParametersResult'[] result + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/realsense2_camera_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/realsense2_camera_msgs.ros new file mode 100644 index 0000000..ed8fde6 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/realsense2_camera_msgs.ros @@ -0,0 +1,30 @@ +realsense2_camera_msgs: + msgs: + IMUInfo + message + 'std_msgs/msg/Header'[] header + float64[] data + float64[] noise_variances + float64[] bias_variances + Extrinsics + message + float64[] rotation + float64[] translation + Metadata + message + 'std_msgs/msg/Header'[] header + string json_data + + srvs: + DeviceInfo + request + response + string device_name + string serial_number + string firmware_version + string usb_type_descriptor + string firmware_update_id + string sensors + string physical_port + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rosbag2_interfaces.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rosbag2_interfaces.ros new file mode 100644 index 0000000..f933808 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rosbag2_interfaces.ros @@ -0,0 +1,54 @@ +rosbag2_interfaces: + msgs: + ReadSplitEvent + message + string closed_file + string opened_file + WriteSplitEvent + message + string closed_file + string opened_file + + srvs: + Seek + request + 'builtin_interfaces/msg/Time'[] time + response + bool success + TogglePaused + request + response + Snapshot + request + response + bool success + SetRate + request + float64 rate + response + bool success + Burst + request + uint64 num_messages + response + uint64 actually_burst + Resume + request + response + Pause + request + response + PlayNext + request + response + bool success + GetRate + request + response + float64 rate + IsPaused + request + response + bool paused + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rosgraph_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rosgraph_msgs.ros new file mode 100644 index 0000000..ba31214 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/rosgraph_msgs.ros @@ -0,0 +1,8 @@ +rosgraph_msgs: + msgs: + Clock + message + 'builtin_interfaces/msg/Time'[] clock + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/sensor_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/sensor_msgs.ros new file mode 100644 index 0000000..a9254f3 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/sensor_msgs.ros @@ -0,0 +1,204 @@ +sensor_msgs: + msgs: + PointCloud + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Point32'[] points + 'sensor_msgs/msg/ChannelFloat32'[] channels + Joy + message + 'std_msgs/msg/Header'[] header + float32[] axes + int32[] buttons + LaserScan + message + 'std_msgs/msg/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 + CameraInfo + message + 'std_msgs/msg/Header'[] header + uint32 height + uint32 width + string distortion_model + float64[] d + float64[] k + float64[] r + float64[] p + uint32 binning_x + uint32 binning_y + 'sensor_msgs/msg/RegionOfInterest'[] roi + JoyFeedbackArray + message + 'sensor_msgs/msg/JoyFeedback'[] array + TimeReference + message + 'std_msgs/msg/Header'[] header + 'builtin_interfaces/msg/Time'[] time_ref + string source + PointCloud2 + message + 'std_msgs/msg/Header'[] header + uint32 height + uint32 width + 'sensor_msgs/msg/PointField'[] fields + bool is_bigendian + uint32 point_step + uint32 row_step + uint8[] data + bool is_dense + CompressedImage + message + 'std_msgs/msg/Header'[] header + string format + uint8[] data + Imu + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Quaternion'[] orientation + float64[] orientation_covariance + 'geometry_msgs/msg/Vector3'[] angular_velocity + float64[] angular_velocity_covariance + 'geometry_msgs/msg/Vector3'[] linear_acceleration + float64[] linear_acceleration_covariance + LaserEcho + message + float32[] echoes + MagneticField + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Vector3'[] magnetic_field + float64[] magnetic_field_covariance + JoyFeedback + message + uint8 type + uint8 id + float32 intensity + FluidPressure + message + 'std_msgs/msg/Header'[] header + float64 fluid_pressure + float64 variance + RelativeHumidity + message + 'std_msgs/msg/Header'[] header + float64 relative_humidity + float64 variance + Range + message + 'std_msgs/msg/Header'[] header + uint8 radiation_type + float32 field_of_view + float32 min_range + float32 max_range + float32 range + NavSatStatus + message + int8 status + uint16 service + ChannelFloat32 + message + string name + float32[] values + JointState + message + 'std_msgs/msg/Header'[] header + string[] name + float64[] position + float64[] velocity + float64[] effort + Image + message + 'std_msgs/msg/Header'[] header + uint32 height + uint32 width + string encoding + uint8 is_bigendian + uint32 step + uint8[] data + MultiDOFJointState + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'geometry_msgs/msg/Transform'[] transforms + 'geometry_msgs/msg/Twist'[] twist + 'geometry_msgs/msg/Wrench'[] wrench + NavSatFix + message + 'std_msgs/msg/Header'[] header + 'sensor_msgs/msg/NavSatStatus'[] status + float64 latitude + float64 longitude + float64 altitude + float64[] position_covariance + uint8 position_covariance_type + Illuminance + message + 'std_msgs/msg/Header'[] header + float64 illuminance + float64 variance + Temperature + message + 'std_msgs/msg/Header'[] header + float64 temperature + float64 variance + PointField + message + string name + uint32 offset + uint8 datatype + uint32 count + RegionOfInterest + message + uint32 x_offset + uint32 y_offset + uint32 height + uint32 width + bool do_rectify + BatteryState + message + 'std_msgs/msg/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 + MultiEchoLaserScan + message + 'std_msgs/msg/Header'[] header + float32 angle_min + float32 angle_max + float32 angle_increment + float32 time_increment + float32 scan_time + float32 range_min + float32 range_max + 'sensor_msgs/msg/LaserEcho'[] ranges + 'sensor_msgs/msg/LaserEcho'[] intensities + + srvs: + SetCameraInfo + request + 'sensor_msgs/msg/CameraInfo'[] camera_info + response + bool success + string status_message + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/shape_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/shape_msgs.ros new file mode 100644 index 0000000..1c80c58 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/shape_msgs.ros @@ -0,0 +1,19 @@ +shape_msgs: + msgs: + Mesh + message + 'shape_msgs/msg/MeshTriangle'[] triangles + 'geometry_msgs/msg/Point'[] vertices + MeshTriangle + message + uint32[] vertex_indices + SolidPrimitive + message + uint8 type + 'geometry_msgs/msg/Polygon'[] polygon + Plane + message + float64[] coef + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/statistics_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/statistics_msgs.ros new file mode 100644 index 0000000..051c020 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/statistics_msgs.ros @@ -0,0 +1,19 @@ +statistics_msgs: + msgs: + StatisticDataPoint + message + uint8 data_type + float64 data + MetricsMessage + message + string measurement_source_name + string metrics_source + string unit + 'builtin_interfaces/msg/Time'[] window_start + 'builtin_interfaces/msg/Time'[] window_stop + 'statistics_msgs/msg/StatisticDataPoint'[] statistics + StatisticDataType + message + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/std_srvs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/std_srvs.ros new file mode 100644 index 0000000..a3b5986 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/std_srvs.ros @@ -0,0 +1,19 @@ +std_srvs: + + srvs: + Empty + request + response + Trigger + request + response + bool success + string message + SetBool + request + bool data + response + bool success + string message + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/stereo_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/stereo_msgs.ros new file mode 100644 index 0000000..e843ac5 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/stereo_msgs.ros @@ -0,0 +1,15 @@ +stereo_msgs: + msgs: + DisparityImage + message + 'std_msgs/msg/Header'[] header + 'sensor_msgs/msg/Image'[] image + float32 f + float32 t + 'sensor_msgs/msg/RegionOfInterest'[] valid_window + float32 min_disparity + float32 max_disparity + float32 delta_d + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/tf2_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/tf2_msgs.ros new file mode 100644 index 0000000..84d3cd6 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/tf2_msgs.ros @@ -0,0 +1,31 @@ +tf2_msgs: + msgs: + TFMessage + message + 'geometry_msgs/msg/TransformStamped'[] transforms + TF2Error + message + uint8 error + string error_string + + srvs: + FrameGraph + request + response + string frame_yaml + + actions: + LookupTransform + goal + string target_frame + string source_frame + 'builtin_interfaces/msg/Time'[] source_time + 'builtin_interfaces/msg/Duration'[] timeout + 'builtin_interfaces/msg/Time'[] target_time + string fixed_frame + bool advanced + result + 'geometry_msgs/msg/TransformStamped'[] transform + 'tf2_msgs/msg/TF2Error'[] error + feedback + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/theora_image_transport.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/theora_image_transport.ros new file mode 100644 index 0000000..9e694b0 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/theora_image_transport.ros @@ -0,0 +1,13 @@ +theora_image_transport: + msgs: + Packet + message + 'std_msgs/msg/Header'[] header + uint8[] data + int32 b_o_s + int32 e_o_s + int64 granulepos + int64 packetno + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/trajectory_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/trajectory_msgs.ros new file mode 100644 index 0000000..f76e065 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/trajectory_msgs.ros @@ -0,0 +1,28 @@ +trajectory_msgs: + msgs: + JointTrajectoryPoint + message + float64[] positions + float64[] velocities + float64[] accelerations + float64[] effort + 'builtin_interfaces/msg/Duration'[] time_from_start + MultiDOFJointTrajectoryPoint + message + 'geometry_msgs/msg/Transform'[] transforms + 'geometry_msgs/msg/Twist'[] velocities + 'geometry_msgs/msg/Twist'[] accelerations + 'builtin_interfaces/msg/Duration'[] time_from_start + JointTrajectory + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'trajectory_msgs/msg/JointTrajectoryPoint'[] points + MultiDOFJointTrajectory + message + 'std_msgs/msg/Header'[] header + string[] joint_names + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'[] points + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/turtlesim.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/turtlesim.ros new file mode 100644 index 0000000..445c805 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/turtlesim.ros @@ -0,0 +1,57 @@ +turtlesim: + msgs: + Color + message + uint8 r + uint8 g + uint8 b + Pose + message + float32 x + float32 y + float32 theta + float32 linear_velocity + float32 angular_velocity + + srvs: + TeleportAbsolute + request + float32 x + float32 y + float32 theta + response + Spawn + request + float32 x + float32 y + float32 theta + string name + response + string name + TeleportRelative + request + float32 linear + float32 angular + response + Kill + request + string name + response + SetPen + request + uint8 r + uint8 g + uint8 b + uint8 width + uint8 off + response + + actions: + RotateAbsolute + goal + float32 theta + result + float32 delta + feedback + float32 remaining + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/unique_identifier_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/unique_identifier_msgs.ros new file mode 100644 index 0000000..0f83696 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/unique_identifier_msgs.ros @@ -0,0 +1,8 @@ +unique_identifier_msgs: + msgs: + UUID + message + uint8[] uuid + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ur_dashboard_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ur_dashboard_msgs.ros new file mode 100644 index 0000000..e55f67f --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ur_dashboard_msgs.ros @@ -0,0 +1,88 @@ +ur_dashboard_msgs: + msgs: + RobotMode + message + int8 mode + ProgramState + message + string state + SafetyMode + message + uint8 mode + + srvs: + GetRobotMode + request + response + 'ur_dashboard_msgs/msg/RobotMode'[] robot_mode + string answer + bool success + IsProgramRunning + request + response + string answer + bool program_running + bool success + GetProgramState + request + response + 'ur_dashboard_msgs/msg/ProgramState'[] state + string program_name + string answer + bool success + RawRequest + request + string query + response + string answer + GetSafetyMode + request + response + 'ur_dashboard_msgs/msg/SafetyMode'[] safety_mode + string answer + bool success + Load + request + string filename + response + string answer + bool success + AddToLog + request + string message + response + string answer + bool success + IsProgramSaved + request + response + string answer + string program_name + bool program_saved + bool success + GetLoadedProgram + request + response + string answer + string program_name + bool success + Popup + request + string message + response + string answer + bool success + + actions: + SetMode + goal + int8 target_robot_mode + bool stop_program + bool play_program + result + bool success + string message + feedback + int8 current_robot_mode + int8 current_safety_mode + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ur_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ur_msgs.ros new file mode 100644 index 0000000..fe05d29 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/ur_msgs.ros @@ -0,0 +1,100 @@ +ur_msgs: + msgs: + MasterboardDataMsg + message + uint32 digital_input_bits + uint32 digital_output_bits + int8 analog_input_range0 + int8 analog_input_range1 + float64 analog_input0 + float64 analog_input1 + int8 analog_output_domain0 + int8 analog_output_domain1 + float64 analog_output0 + float64 analog_output1 + float32 masterboard_temperature + float32 robot_voltage_48v + float32 robot_current + float32 master_io_current + uint8 master_safety_state + uint8 master_onoff_state + Digital + message + uint8 pin + bool state + IOStates + message + 'ur_msgs/msg/Digital'[] digital_in_states + 'ur_msgs/msg/Digital'[] digital_out_states + 'ur_msgs/msg/Digital'[] flag_states + 'ur_msgs/msg/Analog'[] analog_in_states + 'ur_msgs/msg/Analog'[] analog_out_states + ToolDataMsg + message + int8 analog_input_range2 + int8 analog_input_range3 + float64 analog_input2 + float64 analog_input3 + float32 tool_voltage_48v + uint8 tool_output_voltage + float32 tool_current + float32 tool_temperature + uint8 tool_mode + Analog + message + uint8 pin + uint8 domain + float32 state + RobotModeDataMsg + message + uint64 timestamp + bool is_robot_connected + bool is_real_robot_enabled + bool is_power_on_robot + bool is_emergency_stopped + bool is_protective_stopped + bool is_program_running + bool is_program_paused + RobotStateRTMsg + message + float64 time + float64[] q_target + float64[] qd_target + float64[] qdd_target + float64[] i_target + float64[] m_target + float64[] q_actual + float64[] qd_actual + float64[] i_actual + float64[] tool_acc_values + float64[] tcp_force + float64[] tool_vector + float64[] tcp_speed + float64 digital_input_bits + float64[] motor_temperatures + float64 controller_timer + float64 test_value + float64 robot_mode + float64[] joint_modes + + srvs: + SetPayload + request + float32 mass + 'geometry_msgs/msg/Vector3'[] center_of_gravity + response + bool success + SetSpeedSliderFraction + request + float64 speed_slider_fraction + response + bool success + SetIO + request + int8 fun + int8 pin + float32 state + response + bool success + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/vision_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/vision_msgs.ros new file mode 100644 index 0000000..a2ba775 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/vision_msgs.ros @@ -0,0 +1,77 @@ +vision_msgs: + msgs: + BoundingBox2D + message + 'vision_msgs/msg/Pose2D'[] center + float64 size_x + float64 size_y + Detection2D + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/ObjectHypothesisWithPose'[] results + 'vision_msgs/msg/BoundingBox2D'[] bbox + string id + ObjectHypothesisWithPose + message + 'vision_msgs/msg/ObjectHypothesis'[] hypothesis + 'geometry_msgs/msg/PoseWithCovariance'[] pose + Pose2D + message + 'vision_msgs/msg/Point2D'[] position + float64 theta + BoundingBox3D + message + 'geometry_msgs/msg/Pose'[] center + 'geometry_msgs/msg/Vector3'[] size + Detection2DArray + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/Detection2D'[] detections + ObjectHypothesis + message + string class_id + float64 score + BoundingBox2DArray + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/BoundingBox2D'[] boxes + Detection3D + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/ObjectHypothesisWithPose'[] results + 'vision_msgs/msg/BoundingBox3D'[] bbox + string id + Classification + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/ObjectHypothesis'[] results + Detection3DArray + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/Detection3D'[] detections + VisionInfo + message + 'std_msgs/msg/Header'[] header + string method + string database_location + int32 database_version + LabelInfo + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/VisionClass'[] class_map + float32 threshold + VisionClass + message + uint16 class_id + string class_name + Point2D + message + float64 x + float64 y + BoundingBox3DArray + message + 'std_msgs/msg/Header'[] header + 'vision_msgs/msg/BoundingBox3D'[] boxes + + + \ No newline at end of file diff --git a/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/visualization_msgs.ros b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/visualization_msgs.ros new file mode 100644 index 0000000..fabf1c0 --- /dev/null +++ b/de.fraunhofer.ipa.ros.communication.objects/nav2_msgs/visualization_msgs.ros @@ -0,0 +1,113 @@ +visualization_msgs: + msgs: + InteractiveMarkerInit + message + string server_id + uint64 seq_num + 'visualization_msgs/msg/InteractiveMarker'[] markers + ImageMarker + message + 'std_msgs/msg/Header'[] header + string ns + int32 id + int32 type + int32 action + 'geometry_msgs/msg/Point'[] position + float32 scale + 'std_msgs/msg/ColorRGBA'[] outline_color + uint8 filled + 'std_msgs/msg/ColorRGBA'[] fill_color + 'builtin_interfaces/msg/Duration'[] lifetime + 'geometry_msgs/msg/Point'[] points + 'std_msgs/msg/ColorRGBA'[] outline_colors + UVCoordinate + message + float32 u + float32 v + Marker + message + 'std_msgs/msg/Header'[] header + string ns + int32 id + int32 type + int32 action + 'geometry_msgs/msg/Pose'[] pose + 'geometry_msgs/msg/Vector3'[] scale + 'std_msgs/msg/ColorRGBA'[] color + 'builtin_interfaces/msg/Duration'[] lifetime + bool frame_locked + 'geometry_msgs/msg/Point'[] points + 'std_msgs/msg/ColorRGBA'[] colors + string texture_resource + 'sensor_msgs/msg/CompressedImage'[] texture + 'visualization_msgs/msg/UVCoordinate'[] uv_coordinates + string text + string mesh_resource + 'visualization_msgs/msg/MeshFile'[] mesh_file + bool mesh_use_embedded_materials + MeshFile + message + string filename + uint8[] data + InteractiveMarkerUpdate + message + string server_id + uint64 seq_num + uint8 type + 'visualization_msgs/msg/InteractiveMarker'[] markers + 'visualization_msgs/msg/InteractiveMarkerPose'[] poses + string[] erases + InteractiveMarker + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose'[] pose + string name + string description + float32 scale + 'visualization_msgs/msg/MenuEntry'[] menu_entries + 'visualization_msgs/msg/InteractiveMarkerControl'[] controls + MarkerArray + message + 'visualization_msgs/msg/Marker'[] markers + InteractiveMarkerFeedback + message + 'std_msgs/msg/Header'[] header + string client_id + string marker_name + string control_name + uint8 event_type + 'geometry_msgs/msg/Pose'[] pose + uint32 menu_entry_id + 'geometry_msgs/msg/Point'[] mouse_point + bool mouse_point_valid + MenuEntry + message + uint32 id + uint32 parent_id + string title + string command + uint8 command_type + InteractiveMarkerPose + message + 'std_msgs/msg/Header'[] header + 'geometry_msgs/msg/Pose'[] pose + string name + InteractiveMarkerControl + message + string name + 'geometry_msgs/msg/Quaternion'[] orientation + uint8 orientation_mode + uint8 interaction_mode + bool always_visible + 'visualization_msgs/msg/Marker'[] markers + bool independent_marker_orientation + string description + + srvs: + GetInteractiveMarkers + request + response + uint64 sequence_number + 'visualization_msgs/msg/InteractiveMarker'[] markers + + \ No newline at end of file