Evaluation

This page shows the evaluation of rospec’s ability to detect or document misconfigurations in ROS-based robot software.

Methodology

Our evaluation analyzed 182 real-world questions from ROS Answers, the previous primary Q&A platform for the ROS community. We categorized each question based on whether rospec could:

  • Detectable the misconfiguration automatically through static analysis.
  • Document the issue through improved component specification;
  • Not Support the particular issue (beyond current capabilities);
  • Out of Scope / Missing Context the issue was not related to misconfiguration or lacked sufficient context for analysis.

For Detectable and Documentation categories, we created rospec specifications demonstrating how to prevent these real-world problems.

QuestionMisconfigurationStatusSpecification
10924
PARAMETER: Missing PARAMETER: Incorrect NAME: Namespaces NODE: Incorrect CONTEXTUAL: Application-Environment CONTEXTUAL: HARDWARE: Compute
Documentation
plugin type arm_kinematics_constraint_aware_type {
    optional param group: Plugin = default(right_arm_type);
}

type alias Second: double where {_ >= 0.0};
type alias Natural: int where {_ >= 0};

plugin type right_arm_type {
    optional param tip_name: string = "";
    optional param root_name: string = "";
    param kinematics_solver: Plugin;

    param max_solver_iterations: int;
    param max_search_iterations: int;

    optional param robot_description: string = "robot_description";
    optional param allow_valid_collisions: bool = false;
    optional param joint_states_safety_timeout: double = 0.0;
    optional param global_frame: string = "";
    optional param tf_safety_timeout: Second = 0.0;
    optional param use_collision_map: bool = true;
}

plugin type kdlkinematicsplugin {
    optional param kinematics_solver_search_resolution: double = 0.005;
    optional param kinematics_solver_timeout: Second = 0.05;
    optional param kinematics_solver_attemps: Natural = 3;
    optional param namespace: string = "kdl_kinematics_plugin";
}

system {
    plugin instance arm_kinematics_constraint_aware: arm_kinematics_constraint_aware_type {
        param group = right_arm;
    }

    plugin instance right_arm: right_arm_type {
        param tip_name = "right_wrist_link";
        param root_name = "lower_torso_link";
        param kinematics_solver = KDLKinematicsPlugin;

        param max_solver_iterations = 1000;
        param max_search_iterations = 10;
    }

    plugin instance KDLKinematicsPlugin: kdlkinematicsplugin { }
}
11547
MESSAGE: Conflicting-Publishers NAME: Remapping
Detectable
type alias Modes: Enum[SXGA15Hz, VGA30Hz, VGA25Hz, QVGA25Hz, QVGA30Hz, QVGA60Hz, QQVGA25Hz, QQVGA30Hz, QQVGA60Hz];
type alias Second: float;

node type openni_node_type {
    optional param depth_frame_id: string = "/openni_depth_optical_frame";
    optional param rgb_frame_id: string = "/openni_rgb_optical_frame";
    optional param image_mode: Modes = VGA30Hz;
    optional param depth_mode: Modes = VGA30Hz;
    optional param use_indices: bool = false;
    optional param depth_registration: bool = false;
    optional param depth_time_offset: Second where {_ >= -1 and _ <= 1} = 0.0;
    optional param image_time_offset: Second where {_ >= -1 and _ <= 1} = 0.0;

    publishes to camera/depth/points: sensor_msgs/PointCloud2 where {count(publishers(_)) == 1};
}

system {
    node instance openni_node1: openni_node_type {
        param depth_registration = true;
    }

    node instance openni_node2: openni_node_type {
        param depth_registration = true;
        param rgb_frame_id = "/openni_rgb_optical_frame_2";
        param depth_frame_id = "/openni_depth_optical_frame_2";
    }
}
173503
PARAMETER: Missing MESSAGE: Periodic TIME: Frequency
Documentation
type alias Distro: OrderedEnum[Ardent, Bouncy, Crystal, Dashing, Eloquent, Foxy, Galactic, Humble, Iron, Jazzy, Kilted];

type alias Hertz: double;

node type joy_node_type {
    context distribution: Distro;

    optional param autorepeat_rate: Hertz = 0.0;
    optional param deadzone: double where {-1.0 <= _ and _ <= 1.0} = 0.05;
}
190483
PARAMETER: Incorrect
Detectable
node type openni_node_type {
    optional param depth_registration: bool = false;

    publishes to camera/depth/points: sensor_msgs/PointCloud2 where {count(publishers(_)) == 1}; 
}

node type amcl_type {
    optional param depth_registration: bool = false;

    publishes to camera/depth/points: sensor_msgs/PointCloud2 where {count(publishers(_)) == 1}; 
}

system {
    node instance openni_node1: openni_node_type {
        param depth_registration = true;
    }

    node instance amcl: amcl_type {
        param depth_registration = true;
    }
}
201031
PARAMETER: Incorrect TYPES: Color-Format TYPES: Transformations NODE: Missing
Documentation
message alias RGBImage: sensor_msgs/Image {
    field height: uint32 where {_ >= 0};
    field width: uint32 where {_ >= 0};

    field header: std_msgs/Header;
    field encoding: string;
    field is_bigendian: uint8;
    field step: uint32;
    field data: uint8[];
}

type alias Natural: int where {_ >= 0};

node type svo_node_type {
    optional param cam_topic: string = "svo/camera/image_raw";
    optional param grid_size: double = 30;
    optional param max_n_kfs: Natural = 10;
    optional param loba_num_iter: Natural = 0;

    subscribes to content(cam_topic): RGBImage;
}

# The following is an example of how to use the svo_node_type in a system, it doesn't fully address the question issues.
# system {
#    node instance svo: svo_node_type {
#        param cam_topic = "svo/ardrone/front/image_raw";
#    }
# }
210414
PARAMETER: Missing DSL: Navigation-Stack NAME: Namespaces
Documentation
type alias Distro: OrderedEnum[DiamondBlack, Electrict, Fuerte, Groovy, Hydro, Indigo, Jade, Kinetic, Lunar, Melodic, Noetic];

node type move_base_type {
    optional context distribution: Distro = Hydro;

    optional param GlobalPlanner/use_dijkstra: bool = false;
}
217551
MESSAGE: Conflicting-Publishers
Detectable
policy instance depth10qos: qos {
    setting history = KeepLast;
    setting depth = 10;
}

node type worker_type {
    @qos{depth10qos}
    publishes to /mico_arm_driver/in/cartesian_velocity: geometry_msgs/TwistStamped where {count(publishers(_)) == 1};
}

system {
    node instance worker1: worker_type {}
    node instance worker2s: worker_type {}
}
232853
PARAMETER: Dependency PARAMETER: Incorrect DSL: Navigation-Stack CONTEXTUAL: HARDWARE: Mechanical
Detectable
node type move_base_type {
    param cost_scaling_factor: double;
    param inflation_radius: double;
    param robot_radius: double;
} where {
    exists(inflation_radius) == exists(cost_scaling_factor);
    robot_radius <= inflation_radius;
}

system {
    node instance move_base:  move_base_type { }
}
235375
MESSAGE: Conflicting-Publishers
Detectable
node type joint_state_publisher_type {
    publishes to joint_states: sensor_msgs/JointState where {count(publishers(_)) == 1};
}

node type custom_node_type {
    publishes to joint_states: sensor_msgs/JointState where {count(publishers(_)) == 1};
}

system{
    node instance joint_state_publisher: joint_state_publisher_type {}
    node instance custom_node: custom_node_type {}
}
30235
PARAMETER: Missing CALIBRATION: Camera CONTEXTUAL: HARDWARE: Sensors
Documentation
node type uv_cam_node_type {
    optional param format_mode: Enum[RGB, YUYV, MJPG] = RGB;
}
316168
PARAMETER: Missing DSL: Robot-Localization
Documentation
node type ekf_localization_node_type {
    # Parameter that provides an initial state
    param initial_state: int[][];
}
364801
PARAMETER: Dependency PARAMETER: Incorrect DSL: MoveIt CONTEXTUAL: HARDWARE: Actuators CONTEXTUAL: HARDWARE: Mechanical
Detectable
node type move_group_type {
    param elbow_joint/max_acceleration: double where {_ >= 0};
    #param elbow_joint/min_velocity: double;
    optional param elbow_joint/max_velocity: double = 2.0;
    #param angle_wraparound: bool;

    optional param elbow_joint/has_velocity_limits: bool = false;
    optional param elbow_joint/has_acceleration_limits: bool = false;
} where {
     exists(elbow_joint/max_acceleration) -> elbow_joint/has_acceleration_limits;
}

system {
    node instance move_group: move_group_type {
        param elbow_joint/max_acceleration = 0;
        param elbow_joint/max_velocity = 3.14;
        param elbow_joint/has_acceleration_limits = false;
        param elbow_joint/has_velocity_limits = false;
    }
}
108291
NAME: Namespaces NODE: Missing
Detectable
node type stereo_image_proc_type {
    argument manager: string;
}

system {
    node instance stereo_image_proc: stereo_image_proc_type { }
}
11095
PARAMETER: Missing CONTEXTUAL: Simulation-vs-Real
Detectable
node type laser_scan_matcher_node {
    context is_simulation: bool;
    optional param use_sim_time: bool = false;

    broadcast world to base_link;
    listen base_link to laser;
} where {
    is_simulation -> use_sim_time;
}

system {
    node instance laser_scan_matcher: laser_scan_matcher_node {
        context is_simulation = true;
        param use_sim_time = false;
    }
}
12516
MESSAGE: Periodic
Documentation
# turtlesim/Velocity was replaced with geometry_msgs/Twist
type alias RadSeconds : float;

message alias AnnotatedVector3: geometry_msgs/Vector3 {
    field x: RadSeconds;
    field y: RadSeconds;
    field z: RadSeconds;
}

message alias UnitsVelocity: geometry_msgs/Twist {
    field linear: AnnotatedVector3;
    field angular: AnnotatedVector3;
}
142456
TYPES: Color-Format
Detectable
policy instance depth5qos: qos {
    setting history = KeepLast;
    setting depth = 5;
}

policy instance depth1qos: qos {
    setting history = KeepLast;
    setting depth = 1;
}

policy instance RGB8: color_format {
    setting format = RGB8;
}

policy instance Grayscale: color_format {
    setting format = Grayscale;
}

node type openni_camera_driver_depth_type {
    optional param depth_registration: bool = true;

    @qos{depth1qos}
    @color_format{Grayscale}
    publishes to /camera/rgb/image_raw: sensor_msgs/Image;
}

node type custom_node_type {
    @qos{depth5qos}
    @color_format{RGB8}
    subscribes to /camera/rgb/image_raw: sensor_msgs/Image;
}

system {
    node instance custom_node: custom_node_type { }
    node instance openni_camera_driver: openni_camera_driver_depth_type { }
}
164526
PARAMETER: Missing NAME: Remapping NAME: Namespaces
Detectable
node type hector_object_tracker_type {
    optional param distance_to_obstacle_service: string = "get_distance_to_obstacle";

    publishes to visualization_marker: visualization_msgs/Marker;
    consumes service content(distance_to_obstacle_service): hector_nav_msgs/GetDistanceToObstacle;
}

node type hector_map_server_type {
     provides service /hector_map_server/get_distance_to_obstacle: hector_nav_msgs/GetDistanceToObstacle;
}

system {
    node instance hector_object_tracker: hector_object_tracker_type { }
    node instance hector_map_server: hector_map_server_type { }
}
165661
MESSAGE: Conflicting-Publishers DSL: Robot-Localization CALIBRATION: Odometry
Detectable
node type robot_localization_type {
     param imu0_config: bool[4][3];
     param imu0_differential: bool[2][3];
} where {
    imu0_config[1][2] == imu0_differential[1][2];
}

system {
    node instance robot_localization: robot_localization_type {
         param imu0_config = [[false, false, false],
                              [false, false, true],
                              [false, false, false],
                              [false, false, false]];
         param imu0_differential = [[false, false, false], [false, false, false]];
    }
}
185909
DSL: Navigation-Stack CONTEXTUAL: Application-Environment CONTEXTUAL: HARDWARE: Sensors
Detectable
node type hokuyo_node_type {
    context environment: Enum[ObstacleLayout, EmptyLayout] where {_ == ObstacleLayout};
}

system{
    node instance hokuyo_node: hokuyo_node_type {
        context environment = EmptyLayout;
    }
}
188919
PARAMETER: Incorrect CONTEXTUAL: Simulation-vs-Real
Detectable
node type laser_scan_matcher_node_type {
    optional context is_simulation: bool = false;
    optional param use_sim_time: bool = false;
} where {
    is_simulation -> use_sim_time;
}


system {
    node instance laser_scan_matcher_node: laser_scan_matcher_node_type {
        context is_simulation = true;
        param use_sim_time = false;
    }
}
190126
NAME: Remapping
Detectable
node type camera_calibration_type {
    consumes service /camera/set_camera_info: sensor_msgs/SetCameraInfo;
}

system {
    node instance camera_calibration: camera_calibration_type { }
}
12977
PARAMETER: Incorrect DSL: Navigation-Stack
Detectable
type alias Meter: double;

node type move_base_type {
    param local_costmap/min_obstacle_height: Meter;
    param local_costmap/footprint: double[4][2];
} where {
    local_costmap/footprint[0][1] >= local_costmap/min_obstacle_height;
}

system {
    node instance move_base: move_base_type {
        param local_costmap/min_obstacle_height = 0.10;
        param local_costmap/footprint = [[-0.4, -0.4], [-0.4, 0.4], [0.4, 0.4], [0.4, 0.4]];
    }
}
195289
PARAMETER: Missing DSL: Navigation-Stack NAME: Remapping
Detectable
node type amcl_type {
    consumes service static_map: nav_msgs/GetMap;
}

node type map_server_type {
    optional param topic_name: string = "map";
    provides service content(topic_name): nav_msgs/LoadMap;
}

system {
    node instance amcl: amcl_type {
        # Requires a remap to 30lx
    }
    node instance map_server: map_server_type {
        param topic_name = "30lx";
    }
}
200387
PARAMETER: Incorrect DSL: Navigation-Stack NODE: Missing CONTEXTUAL: HARDWARE: Sensors
Detectable
node type obstacle_layer_t {
    optional param z_voxels: int = 0;
    optional param observation_sources: Plugin[] = [];
} where {
    z_voxels == len(observation_sources);
}

system {
    node instance obstacle_layer: obstacle_layer_t {
        param z_voxels = 2;
        param observation_sources = [scan, bump, irring_scan];
    }
    # ... information about each plugin
}
204073
PARAMETER: Incorrect TYPES: Physical-Units TF: Incorrect-Transform DSL: Robot-Localization
Documentation
message alias AnnotatedMessage: nav_msgs/Odometry {
    # ...
    field header: std_msgs/Header;
    field child_frame_id: string;
    field pose: geometry_msgs/PoseWithCovariance;
    field twist: geometry_msgs/TwistWithCovariance;
}

node type ekf_localization_node_type {
    broadcast world_frame to base_link;
}
204321
DSL: Navigation-Stack NAME: Remapping NAME: Namespaces LAUNCH: Includes
Detectable
node type move_base_t {
    publishes to cmd_vel: geometry_msgs/Twist;
}

node type rosaria_node_t {
    subscribes to /RosAria/cmd_vel: geometry_msgs/Twist;
}

system {
    node instance move_base: move_base_t {
        # remaps cmd_vel to ~cmd_vel;
    }
    node instance rosaria_node: rosaria_node_t { }
}
206849
PARAMETER: Missing
Documentation
node type ardrone_autonomy_type {
    optional param enable_navdata_pressure_raw: bool = false;
    publishes to enable_navdata_pressure_raw: ardrone_autonomy/navdata_pressure_raw; 
}
207352
MESSAGE: Format OTHER: Documentation
Documentation
node type gmapping_type {
  # since no publishes are provided, this acts as documentation
  broadcast map to odom;
}
209404
PARAMETER: Missing DSL: Navigation-Stack
Documentation
node type move_base_t {
    optional param base_local_planner: Plugin = default(TrajectoryPlannerROS);
}
209450
TYPES: Physical-Units
Documentation
type alias ImageEncoding16: Enum[RGB16, RGBA16, BGR16, BGRA16, MONO16,
                                16UC1, 16UC2, 16UC3, 16UC4, 16SC1, 16SC2, 16SC3, 16SC4,
                                BAYER_RGGB16, BAYER_BGGR16, BAYER_GBRG16, BAYER_GRBG16
];

type alias ImageEncoding32: Enum[32SC1, 32SC2, 32SC3, 32SC4, 32FC1, 32FC2, 32FC3, 32FC4];

type alias Meter: uint8;
type alias Millimeter: uint8;

message alias ImageWith16Encoding: sensor_msgs/Image {
    field header: std_msgs/Header;
    field encoding: ImageEncoding16;
    field data: Millimeter[];

    field height: uint32;
    field width: uint32;
    field is_bigendian: uint8;
    field step: uint32;
}


message alias ImageWith32Encoding: sensor_msgs/Image {
    field header: std_msgs/Header;
    field encoding: ImageEncoding32;
    field data: Meter[];

    field height: uint32;
    field width: uint32;
    field is_bigendian: uint8;
    field step: uint32;
}
210583
DSL: Navigation-Stack NODE: Incorrect CONTEXTUAL: Simulation-vs-Real
Detectable
node type fake_localization_type {
    context is_simulation: bool where {_ == true};
}

system {
    node instance fake_localization: fake_localization_type {
        context is_simulation = false;
    }
}
214816
PARAMETER: Missing TF: Missing-Transform DSL: Robot-Localization
Detectable
node type ekf_localization {
    optional param twist0: string = "";
    optional param twist0_config: string[] = [false, false, false,
                        false, false, false,
                        true,  true,  true,
                        false, false, false,
                        false, false, false];
} where {
    exists(twist0_config) -> exists(twist0);
}

system {
    node instance ekf_localization_node: ekf_localization {
        param twist0_config = [false, false, false,
                               false, false, false,
                               true, true, false,
                               false, false, true,
                               false, false, false];
    }
}
218573
PARAMETER: Incorrect MESSAGE: Conflicting-Publishers NAME: Remapping
Detectable
node type usb_cam_node {
    publishes to image: sensor_msgs/Image where {count(publishers(_)) == 1};
}

system {
    node instance usb_cam1: usb_cam_node { }
    node instance usb_cam2: usb_cam_node { }
}
221925
DSL: Navigation-Stack
Detectable
type alias MeterSecond : float;

node type dwa_local_planner_type {
    optional param max_vel_x: MeterSecond = 0.55;
    optional param min_vel_x: MeterSecond = 0.0;
}

system {
    node instance dwa_local_planner: dwa_local_planner_type {
        param penalize_negative_x = true;
    }
}
223521
TF: Incorrect-Transform
Detectable
node type kinect2_bridge_type {
    publishes to /kinect2/sd/image_depth_rect: sensor_msgs/Image;
    publishes to /kinect2/sd/camera_info: sensor_msgs/CameraInfo;

    broadcast kinect2_ir_optical_frame to kinect2_link;
}

node type depth_to_pointcloud_type {
    subscribes to /kinect2/sd/image_depth_rect: sensor_msgs/Image;
    subscribes to /kinect2/sd/camera_info: sensor_msgs/CameraInfo;
    publishes to /kinect2/pointcloud: sensor_msgs/PointCloud2;
}

node type kinect2_filtering_type {
    subscribes to /kinect2/pointcloud: sensor_msgs/PointCloud2;
    publishes to /kinect2/pointcloud_filtered: sensor_msgs/PointCloud2;
}

node type pointcloud_to_laserscan_type {
    subscribes to /kinect2/pointcloud_filtered: sensor_msgs/PointCloud2;
    publishes to /scan2: sensor_msgs/LaserScan;
    listen target_frame to kinect2_link;
}

system {
    node instance kinect2_bridge : kinect2_bridge_type { }
    node instance  depth_to_pointcloud: depth_to_pointcloud_type { }
    node instance  pointcloud_to_laserscan: pointcloud_to_laserscan_type { }
}
225375
MESSAGE: No-Publisher
Detectable
node type ekf_localization_node_type {
    subscribes to /set_pose: geometry_msgs/Pose;
}

system {
    node instance ekf_localization_node: ekf_localization_node_type { }
}
225694
DSL: Robot-Localization NODE: Missing CONTEXTUAL: HARDWARE: Sensors
Detectable
node type rtabmap {
     optional param publish_tf: bool = false;

     broadcast map to odom; 
}

node type robot_localization_type {
    param map_frame: string;
    param odom_frame: string;

    broadcast content(map_frame) to content(odom_frame);
}

system {
    node instance rtab: rtabmap { }

    node instance  robot_localization: robot_localization_type {
        param map_frame = "map";
        param odom_frame = "odom";
    }
}
227092
TF: Missing-Transform
Detectable
node type custom_node {
    #subscribes to /tilt_controller/command: std_msgs/Float64;
    broadcast /tilt_laser to laser;
}

node type rviz_type {
    listen base_link to map;
}

system {
    node instance node: custom_node { }
    node instance rviz: rviz_type { }
}
227128
TF: Missing-Transform NAME: Mismatches
Detectable
node type node0_type {
    publishes to /car/odometry: nav_msgs/Odometry;

    broadcast odom to base_footprint;
}

node type node1_type {
    publishes to /car/odometro: nav_msgs/Odometry;

    broadcast odo to base_footprint;
}

node type gps_node_type {
    publishes to /car/gps: sensor_msgs/NavSatFix; # Assumed the message type

    broadcast gps to base_footprint;
}

node type robot_localization_ekf_type {
    subscribes to /car/odometry: nav_msgs/Odometry;
    subscribes to /car/odometro: nav_msgs/Odometry;
    subscribes to /car/gps: sensor_msgs/NavSatFix;

    listen odom to base_footprint;
}

system {
    node instance node0: node0_type { }
    node instance node1: node1_type { }

    node instance gps_node: gps_node_type { }
    node instance robot_localization_ekf: robot_localization_ekf_type { }

    # The arguments and parameters are not define to provide a minimal example of the misconfiguration
}
229722
NAME: Remapping
Detectable
node type gazebo_type {
    argument paused: bool;
    argument use_sim_time: bool;
    argument gui: bool;

    publishes to /odom: nav2_msgs/Odometry;
    publishes to tf: tf2_msgs/TFMessage;

    broadcast odom to base_footprint;
}

node type robot_pose_ekf_type {
     publishes to tf: tf2_msgs/TFMessage;
}

node type gmapping_type {
     subscribes to tf: tf2_msgs/TFMessage where {count(publishers(_)) == 1};
}

system {
    node instance gazebo: gazebo_type {
        argument paused = false;
        argument use_sim_time = true;
        argument gui = true;
    }

    node instance robot_pose_ekf: robot_pose_ekf_type { }

    node instance gmapping: gmapping_type { }
}
231458
PARAMETER: Incorrect CONTEXTUAL: HARDWARE: Compute
Detectable
node type rgbdslam_type {
    optional param topic_image_mono: string = "/camera/rgb/image_color";
    optional param camera_info_topic: string = "/camera/rgb/camera_info";
    optional param topic_image_depth: string = "/camera/depth_registered/sw_registered/image_rect_raw";
    optional param topic_points: string = "";
    optional param base_frame_name: string = "/openni_rgb_optical_frame";
} where {
    exists(topic_image_depth) -> topic_points == "";
}

system {
    node instance rgbdslam: rgbdslam_type {
        param topic_image_mono = "/camera/color/image_raw";
        param camera_info_topic = "/camera/depth/image_raw";
        param topic_image_depth = "/camera/depth/points";
        param topic_points = "/camera_link";
        param base_frame_name = "/camera_link";
    }
}
239888
NAME: Namespaces
Documentation
node type amcl_type {
    context number_of_robots: int;
    optional param tf_prefix: string = "";
} where {
    number_of_robots > 1 == exists(tf_prefix);
}
250138
PARAMETER: Incorrect DSL: Navigation-Stack NODE: Incorrect CONTEXTUAL: Application-Environment CONTEXTUAL: HARDWARE: Sensors
Detectable
plugin type teb_local_planner_t {
    optional param orientation_mode: int = 1;
    optional param global_plan_overwrite_orientation: bool = false;
} where {
    exists(orientation_mode) -> global_plan_overwrite_orientation;
}

system {
    plugin instance teb_local_planner: teb_local_planner_t {
        param orientation_mode = 2;
    }
}
253726
LAUNCH: Duplication
Detectable
node type ratslam_ros_type {
    # ...
}


system {
    node instance ratslam_ros: ratslam_ros_type { }
    node instance ratslam_ros: ratslam_ros_type { }
}
255713
PARAMETER: Incorrect
Detectable
node type amcl_type {
    optional param tf_broadcast: bool = false;
    broadcast map to odom; 
}

node type ekf_node_type {
    broadcast map to odom;
}

system {
    node instance amcl: amcl_type { }
    node instance ekf_node: ekf_node_type { }
}
257637
PARAMETER: Incorrect NAME: Mismatches
Detectable
node type custom_node_type {
    publishes to odom: nav_msgs/Odometry;
    broadcast odom to base_link;
}

node type hector_mapping_type {
    optional param base_frame: string = "base_link";
    optional param odom_frame: string = "odom";
    listen content(base_frame) to content(odom_frame);
    broadcast map to odom;
}

system {
    node instance custom_node: custom_node_type { }
    node instance hector_mapping: hector_mapping_type {
        param odom_frame = "base_link";
    }
}
257935
NAME: Mismatches
Detectable
node type custom_node_type {
    subscribes to imu_data: sensor_msgs/Imu;
}

node type gazebo_ros_imu_type {
    publishes to imu/data: sensor_msgs/Imu;
}

system {
    node instance custom_node: custom_node_type { }
    node instance gazebo: gazebo_ros_imu_type { }
}
259561
NAME: Mismatches
Detectable
node type custom_node_1 {
    publishes to falconPose: geometry_msgs/Pose;
}

node type custom_node_2 {
    subscribes to position: geometry_msgs/Pose;
}

system {
    node instance custom_node1: custom_node_1 { }
    node instance custom_node2: custom_node_2 { }
}
260640
TYPES: Color-Format
Documentation
type alias ImageEncoding16: Enum[RGB16, RGBA16, BGR16, BGRA16, MONO16,
                                16UC1, 16UC2, 16UC3, 16UC4, 16SC1, 16SC2, 16SC3, 16SC4,
                                BAYER_RGGB16, BAYER_BGGR16, BAYER_GBRG16, BAYER_GRBG16
];

type alias ImageEncoding32: Enum[32SC1, 32SC2, 32SC3, 32SC4, 32FC1, 32FC2, 32FC3, 32FC4];

type alias Meter: uint8;
type alias Millimeter: uint8;

message alias ImageWith16Encoding: sensor_msgs/Image {
    field header: std_msgs/Header;
    field encoding: ImageEncoding16;
    field data: Millimeter[];

    field height: uint32;
    field width: uint32;
    field is_bigendian: uint8;
    field step: uint32;
}


message alias ImageWith32Encoding: sensor_msgs/Image {
    field header: std_msgs/Header;
    field encoding: ImageEncoding32;
    field data: Meter[];

    field height: uint32;
    field width: uint32;
    field is_bigendian: uint8;
    field step: uint32;
}
266708
NAME: Namespaces
Documentation
node type image_proc_type {
    optional param queue_size: int = 5;

    subscribes to image_raw: sensor_msgs/Image;
    subscribes to camera_info: sensor_msgs/CameraInfo;

    publishes to image_mono: sensor_msgs/Image;
    publishes to image_rect: sensor_msgs/Image;
    # ...
}
27979
PARAMETER: Dead-Write CONTEXTUAL: HARDWARE: Sensors OTHER: Documentation
Documentation
type alias Rate: int where {_ > 0};

node type sicklms {
    context device_resolution: double;

    optional param use_rep_117: bool = true;
    optional param port: string = "dev/lms200";
    optional param baud: Rate = 38400;
    optional param inverted: bool = false;
    optional param frame_id: string = "laser";
    optional param angle: int = 0;
    optional param resolution: double = 0.0;
    optional param connect_delay: double = 0.0;

    publishes to scan: sensor_msgs/LaserScan;
}
280412
NODE: Missing
Detectable
node type turtlesim_node_type {
    subscribes to turtle2/cmd_vel: geometry_msgs/Twist;
    publishes to turtle2/pose: geometry_msgs/Pose;
}

node type turtle_tf_broadcast_type {
    param turtle: string;
    subscribes to content(turtle): geometry_msgs/Pose;
    broadcast content(turtle) to world;
}

node type turtle_tf_listener {
    publishes to turtle2/cmd_vel: geometry_msgs/Twist;
    listen turtle2 to turtle1;
}

system {
    node instance turtlesim_node: turtlesim_node_type { }
    node instance turtle1_tf_broadcast: turtle_tf_broadcast_type {
        param turtle = "turtle1/pose";
    }
}
28163
PARAMETER: Missing LAUNCH: Includes CONTEXTUAL: Simulation-vs-Real
Detectable
node type planning_scene_warehouse_viewer_t {
    context is_simulation: bool;

    optional argument use_monitor: bool = false;
    optional argument use_collision_map: bool = false;
    optional param use_robot_data: bool = false;

    subscribes to /joint_states: sensor_msgs/JointState;
} where {
    is_simulation -> use_monitor;
    is_simulation -> !use_robot_data;
}

system {
    node instance planning_scene_warehouse_viewer: planning_scene_warehouse_viewer_t {
        context is_simulation = true;
    }
}
283932
TF: Missing-Transform
Detectable
node type custom_node_type {
    broadcast camera_rgb_frame to camera_link;
}

node type freenect_node_type {
    optional param publish_tf: bool = true;

    broadcast camera_link to camera_rgb_frame; 
}

system {
    node instance custom_node: custom_node_type { }
    node instance freenect_node: freenect_node_type { }
}
285062
PARAMETER: Missing DSL: Navigation-Stack NAME: Namespaces
Detectable
node type map_server_type {
    optional param frame_id: string = "map";
    optional param use_map_topic: bool = false;
} where {
    exists(frame_id) -> use_map_topic;
}

system {
    node instance map_server: map_server_type {
        param frame_id = "/map";
        param use_map_topic = false;
    }
}
285266
TYPES: Physical-Units CONTEXTUAL: Simulation-vs-Real OTHER: Documentation
Documentation
type alias MeterPerSecond: float64;
type alias RadianPerSecond: float64;

message alias LinearVector3: geometry_msgs/Vector3 {
    field x: MeterPerSecond;
    field y: MeterPerSecond;
    field z: MeterPerSecond;
}

message alias AngularVector3: geometry_msgs/Vector3 {
    field x: RadianPerSecond;
    field y: RadianPerSecond;
    field z: RadianPerSecond;
}

message alias AnnotatedTwist: geometry_msgs/Twist {
    field linear: LinearVector3;
    field angular: AngularVector3;
}
296720
PARAMETER: Missing OTHER: Simulation
Detectable
node type joint_controller_type {
    context is_simulation: bool;
    optional param use_sim_time: bool = false;
} where {
    is_simulation -> use_sim_time;
}

system {
    node instance joint_controller: joint_controller_type {
        context is_simulation = true;
    }
}
29953
TYPES: Constraints
Documentation
message alias RestrictedPointCloud2: sensor_msgs/PointCloud2 {
    field data: uint8[];
    field header: std_msgs/Header;
    field height: uint32;
    field width: uint32;
    field fields: sensor_msgs/PointField[];
    field is_bigendian: bool;
    field point_step: uint32;
    field row_step: uint32;
    field is_dense: bool;
} where {
    data[0] < data[len(data) - 1];
}

node type laser_scan_matcher_type {
    optional param use_cloud_input: bool = false;
    optional param cloud_range_min: double = 0.1;
    optional param cloud_range_max: double = 50.0;

    subscribes to scan: sensor_msgs/LaserScan;
    subscribes to cloud: RestrictedPointCloud2;
    subscribes to imu_data: sensor_msgs/Imu;
    subscribes to odom: nav_msgs/Odometry;

    listen base_link to laser;
    broadcast world to base_link;
} where {
    !use_cloud_input -> !exists(cloud_range_min);
    !use_cloud_input -> !exists(cloud_range_max);
}
31036
TYPES: Transformations CONTEXTUAL: HARDWARE: Sensors
Documentation
node type gmapping_type {
    context positioning: Enum[Vertical, Horizontal, Tilted] where {_ != Tilted};
}
316037
TF: Incorrect-Transform NAME: Mismatches
Detectable
node type amcl_type {
    # I believe these are actually in params, that then we provide and amcl does the broadcast, but I abstracted that here
    broadcast map to odom;
}

node type static_transform_publisher {
    broadcast map to odom;
}

system {
    node instance amcl: amcl_type { }
    node instance map_to_odom: static_transform_publisher { }
}
319065
PARAMETER: Incorrect DSL: Navigation-Stack
Detectable
node type amcl_type {
    param odom_model_type: Enum[DiffCorrected, OmniCorrected];
    optional param lazer_z_hit: double = 0.95;
    optional param odom_alpha1: double = 0.2;
    optional param odom_alpha2: double = 0.2;
    optional param odom_alpha3: double = 0.2;
    optional param odom_alpha4: double = 0.2;
    optional param odom_alpha5: double = 0.2;
} where {
    odom_model_type == OmniCorrected -> exists(odom_alpha5);
    odom_model_type == DiffCorrected -> odom_alpha1 <= 0.01 and odom_alpha2 <= 0.01 and
                                        odom_alpha3 <= 0.01  and odom_alpha4 <= 0.01;
}

system {
    node instance amcl: amcl_type {
        param odom_model_type = DiffCorrected;
        param odom_alpha1 = 4.0;
        param odom_alpha2 = 0.9;
        param odom_alpha3 = 0.2;
        param odom_alpha4 = 0.2;
        #param odom_alpha5 = 0.2;
    }
}
320389
MESSAGE: Conflicting-Publishers TF: Incorrect-Transform CONTEXTUAL: HARDWARE: Sensors
Detectable
node type rgbd_sync_type {
    publishes to /rgbd_image: sensor_msgs/Image;
}

node type zed_wrapper_node_type {
    publishes to /rgbd_image: sensor_msgs/Image;
}

node type rtabmap_type {
    subscribes to rgbd_image: sensor_msgs/Image where {count(publishers(_)) == 1};
}

system {
    node instance rgbd_sync: rgbd_sync_type { }
    node instance zed_wrapper_node: zed_wrapper_node_type { }
    node instance rtabmap: rtabmap_type {
        #remaps rgbd_image to /rgbd_image;
    }
}
325712
PARAMETER: Incorrect TF: Incorrect-Transform
Detectable
node type ekf_localization_node_type {
    broadcast map to odom;
    broadcast odom to base_link; # Abstracted, these are set in parameters, but in this case the configuration is this one
}

node type static_transform_publisher {
    broadcast gps_enu to odom;
}

system {
    node instance ekf_localization_node: ekf_localization_node_type { }
    node instance static_transform: static_transform_publisher { }
}
33175
CONTEXTUAL: HARDWARE: Compute
Detectable
node type rgbdslam_type {
    param fixed_frame_name: string;
    param ground_truth_frame_name: string;
    param base_frame_name: string;
    optional param fixed_camera: bool = false;
} where {
    base_frame_name == "odom" -> !exists(fixed_camera);
}

system {
    node instance rgbdslam: rgbdslam_type {
        param fixed_frame_name = "/map";
        param ground_truth_frame_name = "";
        param base_frame_name = "odom";
        param fixed_camera = true;
    }
}
336055
OTHER: Documentation
Documentation
type alias Radian: float;

node type imu_compass_driver_type {
    optional param /imu/declination: Radian = 0.0;
}
336221
NAME: Remapping
Detectable
node type move_base_type {
    publishes to initialpose: geometry_msgs/PoseWithCovarianceStamped;
}

node type new_amcl_type {
    # argument model: Enum[Burger, Waffle, WafflePi];
    # argument move_forward_only: bool = false;

    subscribes to initialpose_dqn: geometry_msgs/PoseWithCovarianceStamped;
}

system {
    node instance move_base: move_base_type {
        #publishes to initialpose: geometry_msgs/PoseWithCovarianceStamped;
    }

    node instance amcl: new_amcl_type {
        # argument model: Enum[Burger, Waffle, WafflePi];
        # argument move_forward_only: bool = false;
        #subscribes to initialpose_dqn: geometry_msgs/PoseWithCovarianceStamped;
    }
}
340683
MESSAGE: Conflicting-Publishers TF: Duplication
Detectable
node type local_costmap_t {
    param global_frame: string;
    param robot_base_frame: string;

    broadcast content(global_frame) to content(robot_base_frame);
}

node type global_costmap_t {
    param global_frame: string;
    param robot_base_frame: string;

    broadcast content(global_frame) to content(robot_base_frame);
}

node type amcl_type {
    param base_frame_id: string;
    param global_frame_id: string;
}

system {
    node instance local_costmap: local_costmap_t {
        param global_frame = "odom";
        param robot_base_frame = "base_link";
    }

    node instance global_costmap: global_costmap_t {
        param global_frame = "/map";
        param robot_base_frame = "base_link";
    }

    node instance amcl: amcl_type {
        param base_frame_id = "base_link";
        param global_frame_id = "/map";
    }
}
350740
PARAMETER: Incorrect DSL: Robot-Localization
Detectable
node type navsat_transform_node_type {
    context version: OrderedEnum[V2, V221, V223];
    context yaw_orientation: Enum[North, East, West, South];

    param yaw_offset: double;
} where {
    (version >= V221) -> (yaw_orientation == East -> yaw_offset == 0);
    (version >= V221) -> (yaw_orientation != East -> yaw_offset != 0);
    (version <= V221) -> (yaw_orientation == North -> yaw_offset == 0);
    (version <= V221) -> (yaw_orientation != North -> yaw_offset != 0);
}

system {
    node instance navsat_transform_node: navsat_transform_node_type {
        context version = V221;
        context yaw_orientation = East;
        param yaw_offset = 3.14159265359;
    }
}
360477
NAME: Mismatches
Detectable
node type laserscan_multi_merger_type {
    publishes to laserscan_multi_merger/parameter_descriptions: dynamic_reconfigure/ConfigDescription;
    publishes to laserscan_multi_merger/parameter_updates: dynamic_reconfigure/Config;
    publishes to merged_cloud: sensor_msgs/PointCloud2;
    publishes to rosout: rosgraph_msgs/Log;
    publishes to scan_multi: sensor_msgs/MultiEchoLaserScan;
}

node type ira_laser_tools_type {
    optional param destination_frame: string = "cart_frame";
    optional param cloud_destination_topic: string = "/merged_cloud";
    optional param scan_destination_topic: string = "scan_multi";
    optional param laserscan_topics: string[] = ["/scansx", "/scandx"];
    optional param angle_min: double = -2.0;
    optional param angle_max: double = 2.0;
    optional param angle_increment: double = 0.0058;
    optional param scan_time: double = 0.033333;
    optional param range_min: double = 0.30;
    optional param range_max: double = 50.0;

    subscribes to content(laserscan_topics[0]): sensor_msgs/LaserScan;
    subscribes to content(laserscan_topics[1]): sensor_msgs/LaserScan;
} where {
    angle_min < angle_max;
    range_min < range_max;
}

system {
    node instance laserscan_multi_merger:  laserscan_multi_merger_type { }
    node instance ira_laser_tools: ira_laser_tools_type {
        param laserscan_topics = ["/sensor_1/points", "/sensor_2/points"];
    }
}
374209
LAUNCH: Arguments
Documentation
node type component_manager_type {
    optional argument use_intra_process_comms: bool = false;
}
378462
PARAMETER: Incorrect DSL: Robot-Localization NAME: Mismatches CONTEXTUAL: HARDWARE: Sensors
Detectable
node type ekf_filter_node_type {
    optional param world_frame: string = "odom";
}

system {
    node instance ekf_filter_node:  ekf_filter_node_type {
        param worl_frame = "map";
    }
}
379101
TF: Missing-Transform NAME: Remapping
Detectable
node type robot_state_publisher_type {
    context number_of_robots: int;
    optional param tf_prefix: string = "";
} where {
    number_of_robots > 1 -> exists(tf_prefix);
}

system {
    node instance robot_state_publisher: robot_state_publisher_type {
        context number_of_robots = 2;
    }
}
390380
PARAMETER: Incorrect
Detectable
node type op_motion_simulator_type {
    context object_avoidance: bool;

    optional param simObjNumber: int = 5;
    optional param GaussianErrorFactor: int = 0;
    optional param pointCloudPointsNumber: int = 75;
    optional param useNavGoalToSetStaticObstacle: bool = true;
} where {
    object_avoidance -> !useNavGoalToSetStaticObstacle;
}

system {
    node instance op_motion_simulation: op_motion_simulator_type {
        context object_avoidance = true;
    }
}
393902
PARAMETER: Incorrect DSL: Robot-Localization CALIBRATION: Odometry CONTEXTUAL: HARDWARE: Sensors
Detectable
node type ekf_filter_node_type {
    param odom0_config: bool[];
    optional param two_d_mode: bool = false;
} where {
    two_d_mode -> odom0_config[6] and odom0_config[7];
}

system {
    node instance ekf_filter_node: ekf_filter_node_type {
        param odom0_config =
                   [false,  false,  false,
                    false, false, false,
                    false, false, false,
                    false, false, true,
                    false, false, false];
        param two_d_mode = true;
    }
}
401185
PARAMETER: Missing PARAMETER: Defaults DSL: Navigation-Stack
Detectable
node type amcl_type {
    optional param set_initial_pose: bool = false;
    optional param always_reset_initial_pose: bool = false;

    optional param initial_pose: geometry_msgs/Pose = geometry_msgs/Pose {
        position = geometry_msgs/Point {
            x = 0.0,
            y = 0.0,
            theta = 0.0,
        },
        orientation = geometry_msgs/Quaternion {
            x = 0.0,
            y = 0.0,
            z = 0.0,
            w = 0.0,
        },
    };

    subscribes to initialpose: geometry_msgs/PoseWithCovarianceStamped;
} where {
    exists(initial_pose) -> set_initial_pose;
    exists(initial_pose) and set_initial_pose -> always_reset_initial_pose;
}

system {
    node instance amcl: amcl_type {
        param set_initial_pose = false;
        param always_reset_initial_pose = false;
        # Placeholder parameters here, no longer available on Github
        param initial_pose = geometry_msgs/Pose {
            position = geometry_msgs/Point {
                x = 1.0,
                y = 1.0,
                z = 1.0,
            },
            orientation = geometry_msgs/Quaternion {
                x = 1.0,
                y = 1.0,
                z = 1.0,
                w = 1.0,
            },
        };
    }
}
405765
DSL: Navigation-Stack NAME: Remapping OTHER: Documentation
Detectable
node type custom_node_type {
    subscribes to /robo/cmd_vel: geometry_msgs/Twist;
}

# We are not sure what the controller is, but independently of the controller it publishes to cmd_vel, according to the question
node type nav2_controller_type {
    publishes to /cmd_vel: geometry_msgs/Twist;
}

system {
    node instance custom_node: custom_node_type { }
    node instance nav2_controller: nav2_controller_type {
        # missing: remaps /cmd_vel to /robo/cmd_vel;
    }
}
41000
TF: Incorrect-Transform
Detectable
node type amcl_type {
    optional param odom: string = "odom";
    optional param map: string = "map";

    broadcast content(odom) to base_link;
    broadcast content(map) to content(odom);
}

node type custom_node_type {
    broadcast odom to odom_error;
}

system {
    node instance amcl: amcl_type {
        param odom = "odom_error";
    }
    node instance custom_node: custom_node_type { }
}
45556
DSL: Navigation-Stack NAME: Mismatches
Detectable
message MoveBaseAction {
    request field goal: move_base_msgs/MoveBaseGoal;
    response field result: move_base_msgs/MoveBaseResult;
    feedback field feedback: move_base_msgs/MoveBaseFeedback;
}

node type action_server_type {
    provides service move_base: MoveBaseAction;
}

node type simple_move_type {
    consumes service SimpleActionClient: MoveBaseAction;
}

system {
    node instance action_server: action_server_type { }
    node instance simple_move: simple_move_type { }
}
53228
PARAMETER: Incorrect
Detectable
node type rgbdslam_type {
    optional param individual_cloud_out_topic: string = "topic_points";
    optional param store_pointclouds: bool = true;

    publishes to content(individual_cloud_out_topic): sensor_msgs/PointCloud2; 
}

node type custom_node_type {
    # This is used to mimic the attempt to access the information from this topic
    subscribes to /rgbdslam/batch_clouds: sensor_msgs/PointCloud2;
}

system {
    node instance rgbdslam: rgbdslam_type {
        #param individual_cloud_out_topic = "/rgbdslam/batch_clouds";
        param store_pointclouds = false;
    }

    node instance custom_node: custom_node_type { }
}
59087
PARAMETER: Incorrect CONTEXTUAL: HARDWARE: Sensors
Documentation
node type hokuyo_node_type {
    context sensor_max_angle_fov: double;
    context sensor_min_angle_fov: double;

    param min_ang_limit: double;
    param max_ang_limit: double;
} where {
    min_ang_limit <= sensor_min_angle_fov;
    max_ang_limit <= sensor_max_angle_fov;
}
63179
TF: Incorrect-Transform NAME: Namespaces OTHER: Simulation
Detectable
node type rviz_type {
    context number_of_systems: int;
    optional param tf_prefix: string = "";
} where {
    number_of_systems > 1 -> exists(tf_prefix);
}

system {
    node instance rviz: rviz_type {
        context number_of_systems = 2;
    }
}
66176
PARAMETER: Missing LAUNCH: Arguments OTHER: Simulation
Detectable
node type hector_mapping_type {
    context is_simulation: bool;
    optional param use_sim_time: bool = false;
} where {
    is_simulation -> use_sim_time;
}

system {
    node instance hector_mapping: hector_mapping_type {
        context is_simulation = true;
    }
}
9711
TYPES: Constraints
Documentation
message alias RestrictedQuaternion: geometry_msgs/Quaternion {
    field x: float64;
    field y: float64;
    field z: float64;
    field w: float64;
} where {
    (x + y + z + w) != 0;
}
98736
PARAMETER: Incorrect TYPES: Constraints TF: Incorrect-Transform NODE: Missing
Detectable
node type amcl_type {
    broadcast map to odom;
    broadcast odom to base_link; 
}

node type static_transform_publisher_type {
    broadcast map to odom;
}

system {
    node instance amcl: amcl_type { }
    node instance map_to_odom: static_transform_publisher_type { }
}