From bfe0f7c27cdd055848ac21c44af5d099856171b7 Mon Sep 17 00:00:00 2001 From: fke-fs Date: Thu, 17 Jan 2019 12:20:17 +0100 Subject: [PATCH] raw-mini added --- .../raw-mini/config/base_joint_limits.yaml | 0 .../raw-mini/config/base_laser_filter.yaml | 7 + .../collision_velocity_filter_params.yaml | 19 + .../config/footprint_observer_params.yaml | 11 + .../config/joint_state_publisher.yaml | 2 + .../robots/raw-mini/config/joy.yaml | 2 + .../raw-mini/config/local_costmap_params.yaml | 49 ++ .../raw-mini/config/scan_unifier_config.yaml | 3 + .../robots/raw-mini/config/teleop.yaml | 33 + .../raw-mini/config/twist_mux_locks.yaml | 26 + .../raw-mini/config/twist_mux_topics.yaml | 43 ++ .../raw-mini/config/velocity_smoother.yaml | 23 + .../robots/raw-mini/raw-mini.rviz | 601 ++++++++++++++++++ .../raw-mini/urdf/properties.urdf.xacro | 15 + .../robots/raw-mini/urdf/raw-mini.urdf.xacro | 23 + 15 files changed, 857 insertions(+) create mode 100644 cob_hardware_config/robots/raw-mini/config/base_joint_limits.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/base_laser_filter.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/collision_velocity_filter_params.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/footprint_observer_params.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/joint_state_publisher.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/joy.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/local_costmap_params.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/scan_unifier_config.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/teleop.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/twist_mux_locks.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/twist_mux_topics.yaml create mode 100644 cob_hardware_config/robots/raw-mini/config/velocity_smoother.yaml create mode 100644 cob_hardware_config/robots/raw-mini/raw-mini.rviz create mode 100644 cob_hardware_config/robots/raw-mini/urdf/properties.urdf.xacro create mode 100644 cob_hardware_config/robots/raw-mini/urdf/raw-mini.urdf.xacro diff --git a/cob_hardware_config/robots/raw-mini/config/base_joint_limits.yaml b/cob_hardware_config/robots/raw-mini/config/base_joint_limits.yaml new file mode 100644 index 000000000..e69de29bb diff --git a/cob_hardware_config/robots/raw-mini/config/base_laser_filter.yaml b/cob_hardware_config/robots/raw-mini/config/base_laser_filter.yaml new file mode 100644 index 000000000..3ac10129f --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/base_laser_filter.yaml @@ -0,0 +1,7 @@ +scan_filter_chain: + - name: range + type: LaserScanRangeFilter + params: + use_message_range_limits: false + upper_threshold: 10.0 + upper_replacement_value: 10.0 diff --git a/cob_hardware_config/robots/raw-mini/config/collision_velocity_filter_params.yaml b/cob_hardware_config/robots/raw-mini/config/collision_velocity_filter_params.yaml new file mode 100644 index 000000000..7086eaf09 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/collision_velocity_filter_params.yaml @@ -0,0 +1,19 @@ +#where to look for costmap parameters +costmap_parameter_source: "/local_costmap_node/costmap" + +#frequency at which the get_footprint service should be called +footprint_update_frequency: 0.1 + +#Parameters specifying slow down behaviour +pot_ctrl_vmax: 0.6 #default: 0.6 +pot_ctrl_vtheta_max: 0.8 #default: 0.8 +pot_ctrl_kv: 2.5 #damping default: 1.0 +pot_ctrl_kp: 3.0 #stiffness default: 2.0 +pot_ctrl_virt_mass: 0.5 #default: 0.8 +max_acceleration: [0.3, 0.3, 0.4] + +#Parameters specifying collision velocity filter +influence_radius: 2.0 #[m] distance from robot_center +obstacle_damping_dist: 0.3 # used as slow-down dist +stop_threshold: 0.05 #[m] +use_circumscribed_threshold: 0.2 #[rad/s] scan for obstacles in circumscribed radius of robot even when tube filter is enabled during fast rotations diff --git a/cob_hardware_config/robots/raw-mini/config/footprint_observer_params.yaml b/cob_hardware_config/robots/raw-mini/config/footprint_observer_params.yaml new file mode 100644 index 000000000..031ddfa45 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/footprint_observer_params.yaml @@ -0,0 +1,11 @@ +# node from which initial footprint is read +footprint_source: /local_costmap_node/costmap + +# +robot_base_frame: /base_link +# wait until tf from robot_base_frame to farthest_frame is available +farthest_frame: /base_link +# frames to check for footprint adjustment +#frames_to_check: /arm_forearm_link /arm_wrist_1_link /arm_wrist_2_link /arm_wrist_3_link /arm_ee_link +epsilon: 0.01 + diff --git a/cob_hardware_config/robots/raw-mini/config/joint_state_publisher.yaml b/cob_hardware_config/robots/raw-mini/config/joint_state_publisher.yaml new file mode 100644 index 000000000..7323d80b6 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/joint_state_publisher.yaml @@ -0,0 +1,2 @@ +rate: 100 #Hz +source_list: [/base/joint_states] diff --git a/cob_hardware_config/robots/raw-mini/config/joy.yaml b/cob_hardware_config/robots/raw-mini/config/joy.yaml new file mode 100644 index 000000000..f1ac16012 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/joy.yaml @@ -0,0 +1,2 @@ +dev: /dev/input/js0 +deadzone: 0.12 diff --git a/cob_hardware_config/robots/raw-mini/config/local_costmap_params.yaml b/cob_hardware_config/robots/raw-mini/config/local_costmap_params.yaml new file mode 100644 index 000000000..f2af4749b --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/local_costmap_params.yaml @@ -0,0 +1,49 @@ +# global information +global_frame: /base_link +robot_base_frame: /base_footprint +update_frequency: 5.0 +publish_frequency: 5.0 + +# local map settings +static_map: false +rolling_window: true +width: 5.0 +height: 5.0 +resolution: 0.07 + +# footprint and range +footprint: [[0.165,0.115],[-0.165,0.115],[-0.165,-0.115],[0.165,-0.115]] #[m] +footprint_padding: 0.02 #[m] + +#layers +plugins: + +# The obstacle layer tracks the obstacles as read by the sensor data. The ObstacleCostmapPlugin marks and +# raytraces obstacles in two dimensions, while the VoxelCostmapPlugin does so in three dimensions. +- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"} + +obstacle_layer: + + # Definition of the sensors/observation sources + observation_sources: laser_scan + + # Parameters of the source: laser_scan_front + laser_scan_front: + sensor_frame: laser_link # The frame of the origin of the sensor, default: "" + topic: /scan # The topic on which sensor data comes in for this source, default: source_name + data_type: LaserScan # The data type associated with the topic, default: "PointCloud" + marking: true # Whether or not this observation is used to mark obstacles, default: true + clearing: true # Whether or not this observation is used to clear out freespace, default: false + + + # The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters + obstacle_range: 5.0 + + # The default range in meters at which to raytrace out obstacles from the map using sensor data + raytrace_range: 5.0 + + # What map type to use. "voxel" or "costmap" are the supported types, with the difference between them being a 3D-view of the world vs. a 2D-view of the world + map_type: costmap + + # The maximum height in meters of a sensor reading considered valid. + max_obstacle_height: 2.0 diff --git a/cob_hardware_config/robots/raw-mini/config/scan_unifier_config.yaml b/cob_hardware_config/robots/raw-mini/config/scan_unifier_config.yaml new file mode 100644 index 000000000..9c36e8702 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/scan_unifier_config.yaml @@ -0,0 +1,3 @@ +#Scan_unifier_config-parameters + +input_scans: ["/scan"] diff --git a/cob_hardware_config/robots/raw-mini/config/teleop.yaml b/cob_hardware_config/robots/raw-mini/config/teleop.yaml new file mode 100644 index 000000000..8a488dbbb --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/teleop.yaml @@ -0,0 +1,33 @@ +#raw-mini +########## +# common params +run_factor: 2.0 +apply_ramp: false +joy_num_buttons: 12 +joy_num_axes: 6 +joy_num_modes: 1 + +# axes +axis_vx: 4 +axis_vy: 3 +axis_vz: 5 +axis_roll: 4 +axis_pitch: 3 +axis_yaw: 0 + +# buttons +deadman_button: 5 +safety_button: 6 +init_button: 9 + +#mode1: Base +run_button: 7 + +components: { + base: { + twist_topic_name: '/base/twist_mux/command_teleop_joy', + twist_safety_topic_name: '/base/twist_mux/command_teleop_joy', + twist_max_velocity: [0.5, 0.5, 0.5], + twist_max_acc: [0.5, 0.5, 0.7] + } +} diff --git a/cob_hardware_config/robots/raw-mini/config/twist_mux_locks.yaml b/cob_hardware_config/robots/raw-mini/config/twist_mux_locks.yaml new file mode 100644 index 000000000..d61b1da58 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/twist_mux_locks.yaml @@ -0,0 +1,26 @@ +# Locks to stop the twist inputs. +# For each lock: +# - topic : input topic that provides the lock; it must be of type std_msgs::Bool?!!! +# - timeout : == 0.0 -> not used +# > 0.0 -> the lock is supposed to published at a certain frequency in order +# to detect that the publisher is alive; the timeout in seconds allows +# to detect that, and if the publisher dies we will enable the lock +# - priority: priority in the range [0, 255], so all the topics with priority lower than it +# will be stopped/disabled + +locks: +- + name : pause_navigation + topic : twist_mux/locks/pause_navigation + timeout : 0.0 + priority: 21 +- + name : pause_teleop + topic : twist_mux/locks/pause_teleop + timeout : 0.0 + priority: 101 +- + name : pause_all + topic : twist_mux/locks/pause_all + timeout : 0.0 + priority: 255 diff --git a/cob_hardware_config/robots/raw-mini/config/twist_mux_topics.yaml b/cob_hardware_config/robots/raw-mini/config/twist_mux_topics.yaml new file mode 100644 index 000000000..9704c12c7 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/twist_mux_topics.yaml @@ -0,0 +1,43 @@ +# Input topics handled/muxed. +# For each topic: +# - name : name identifier to select the topic +# - topic : input topic of geometry_msgs::Twist type +# - timeout : timeout in seconds to start discarding old messages, and use 0.0 speed instead +# - priority: priority in the range [0, 255]; the higher the more priority over other topics + +topics: +- + name : collision_velocity_filter + topic : twist_mux/command_safe + timeout : 0.25 + priority: 10 +- + name : navigation + topic : twist_mux/command_navigation + timeout : 0.25 + priority: 20 +- + name : syncmm # cob_twist_controller + topic : twist_mux/command_syncmm + timeout : 0.5 + priority: 60 +- + name : script_server + topic : twist_mux/command_script_server + timeout : 0.5 + priority: 70 +- + name : teleop_keyboard + topic : twist_mux/command_teleop_keyboard + timeout : 0.5 + priority: 80 +- + name : teleop_android + topic : twist_mux/command_teleop_android + timeout : 0.5 + priority: 90 +- + name : teleop_joystick + topic : twist_mux/command_teleop_joy + timeout : 0.25 + priority: 100 diff --git a/cob_hardware_config/robots/raw-mini/config/velocity_smoother.yaml b/cob_hardware_config/robots/raw-mini/config/velocity_smoother.yaml new file mode 100644 index 000000000..e825e90be --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/config/velocity_smoother.yaml @@ -0,0 +1,23 @@ +# Example configuration: +# - velocity limits are around a 10% above the physical limits +# - acceleration limits are just low enough to avoid jerking + +# Mandatory parameters +speed_lim_vx: 1.0 +speed_lim_vy: 1.0 +speed_lim_w: 1.0 + +accel_lim_vx: 0.5 +accel_lim_vy: 0.5 +accel_lim_w: 0.5 + +# Optional parameters +frequency: 100.0 +decel_factor: 1.5 #used if zero velocity is received or goal velocity is far away from current velocity +decel_factor_safe: 3.5 #used if no velocity commands received (eg. no deadman on joystick) + +# Robot velocity feedback type: +# 0 - none +# 1 - odometry +# 2 - end robot commands +robot_feedback: 1 \ No newline at end of file diff --git a/cob_hardware_config/robots/raw-mini/raw-mini.rviz b/cob_hardware_config/robots/raw-mini/raw-mini.rviz new file mode 100644 index 000000000..0fe59d78f --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/raw-mini.rviz @@ -0,0 +1,601 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /TF1/Frames1 + - /Camera1 + Splitter Ratio: 0.652605 + Tree Height: 663 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan Rear +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + arm_0_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_7_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_laser_front_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_laser_rear_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_laser_top_link: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_axis_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + head_cam3d_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_cam3d_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_cam_reference_link: + Alpha: 1 + Show Axes: false + Show Trail: false + head_color_camera_l_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_color_camera_l_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_color_camera_r_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_color_camera_r_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_cover_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_finger_11_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_finger_12_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_finger_13_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_finger_21_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_finger_22_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_finger_23_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_grasp_link: + Alpha: 1 + Show Axes: false + Show Trail: false + sdh_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_thumb_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_thumb_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_thumb_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sdh_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + torso_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + torso_lower_neck_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + torso_upper_neck_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tray_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tray_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tray_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tray_phidgets_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tray_phidgets_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tray_phidgets_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tray_phidgets_4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + tray_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 0.7 + Class: rviz/Map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: x + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Max Color: 0; 255; 0 + Max Intensity: 10.454 + Min Color: 0; 255; 0 + Min Intensity: 0.227896 + Name: LaserScan Front + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.01 + Style: Spheres + Topic: /base_laser_front/scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 255; 0 + Min Intensity: 0 + Name: LaserScan Rear + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.025 + Style: Spheres + Topic: /base_laser_rear/scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan Top + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.025 + Style: Spheres + Topic: /base_laser_top/scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Arrow Length: 0.3 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Name: PoseArray + Topic: /particlecloud + Value: true + - Alpha: 1 + Class: rviz/GridCells + Color: 255; 0; 0 + Enabled: true + Name: Obstacles + Topic: /move_base/local_costmap/obstacles + Value: true + - Alpha: 1 + Class: rviz/GridCells + Color: 0; 0; 255 + Enabled: true + Name: Inflated Obstacles + Topic: /move_base/local_costmap/inflated_obstacles + Value: true + - Class: rviz/Axes + Enabled: true + Length: 1 + Name: Axes map origin + Radius: 0.1 + Reference Frame: /map + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 255; 0 + Enabled: true + Name: Path dwa global + Topic: /move_base/DWAPlannerROS/global_plan + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 0; 255 + Enabled: true + Name: Path dwa local + Topic: /move_base/DWAPlannerROS/local_plan + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 255; 0 + Enabled: true + Name: Path tr global + Topic: /move_base/TrajectoryPlannerROS/global_plan + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 0; 255 + Enabled: true + Name: Path tr local + Topic: /move_base/TrajectoryPlannerROS/local_plan + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /light_controller/marker + Name: Marker Light + Namespaces: + {} + Queue Size: 100 + Value: true + - Class: rviz/InteractiveMarkers + Enable Transparency: true + Enabled: false + Name: InteractiveMarkers + Show Axes: false + Show Descriptions: true + Show Visual Aids: false + Update Topic: /cob_interactive_teleop/update + Value: false + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Name: RobotModel + Robot Description: table_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /stereo/left/image_color + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Value: true + Visibility: + Axes map origin: true + Grid: true + Inflated Obstacles: true + InteractiveMarkers: true + LaserScan Front: true + LaserScan Rear: true + LaserScan Top: true + Map: true + Marker Light: true + Obstacles: true + Path dwa global: true + Path dwa local: true + Path tr global: true + Path tr local: true + PoseArray: true + RobotModel: true + TF: true + Value: true + Zoom Factor: 1 + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: /base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.58411 + Focal Point: + X: 0.646932 + Y: 0.446475 + Z: 0.000559447 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.9598 + Target Frame: + Value: Orbit (rviz) + Yaw: 5.81858 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Displays: + collapsed: false + Height: 876 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000019500000326fc0200000007fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000326000000dd00fffffffb0000000c00430061006d00650072006100000002a5000000cd0000001600fffffffb0000000c00430061006d006500720061010000028a000000c40000000000000000000000010000010f00000326fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000326000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000004640000032600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1535 + X: 58 + Y: 24 diff --git a/cob_hardware_config/robots/raw-mini/urdf/properties.urdf.xacro b/cob_hardware_config/robots/raw-mini/urdf/properties.urdf.xacro new file mode 100644 index 000000000..d66d41c9e --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/urdf/properties.urdf.xacro @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cob_hardware_config/robots/raw-mini/urdf/raw-mini.urdf.xacro b/cob_hardware_config/robots/raw-mini/urdf/raw-mini.urdf.xacro new file mode 100644 index 000000000..e0a8fbad6 --- /dev/null +++ b/cob_hardware_config/robots/raw-mini/urdf/raw-mini.urdf.xacro @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + +