mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
updated model for rviz
This commit is contained in:
@@ -69,6 +69,7 @@ Two scripts inside the "scout_bringup/scripts" folder are provided for easy setu
|
|||||||
|
|
||||||
```
|
```
|
||||||
$ sudo apt install ros-melodic-teleop-twist-keyboard
|
$ sudo apt install ros-melodic-teleop-twist-keyboard
|
||||||
|
$ sudo apt-get install ros-melodic-joint-state-publisher-gui
|
||||||
```
|
```
|
||||||
|
|
||||||
Change ros-melodic-* in the command to ros-kinetic-* if you're using ROS Kinetic.
|
Change ros-melodic-* in the command to ros-kinetic-* if you're using ROS Kinetic.
|
||||||
|
|||||||
@@ -26,10 +26,10 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
|
|||||||
|
|
||||||
<launch>
|
<launch>
|
||||||
<arg name="model" />
|
<arg name="model" />
|
||||||
<arg name="gui" default="False" />
|
|
||||||
<param name="robot_description" command="$(find xacro)/xacro '$(find scout_description)/urdf/scout_v2.xacro'" />
|
<param name="robot_description" command="$(find xacro)/xacro '$(find scout_description)/urdf/scout_v2.xacro'" />
|
||||||
<param name="use_gui" value="$(arg gui)"/>
|
<!-- <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node> -->
|
||||||
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
|
<node name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" ></node>
|
||||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
||||||
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find scout_description)/rviz/model_display.rviz" />
|
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find scout_description)/rviz/model_display.rviz" />
|
||||||
</launch>
|
</launch>
|
||||||
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@@ -170,25 +170,25 @@ Visualization Manager:
|
|||||||
Views:
|
Views:
|
||||||
Current:
|
Current:
|
||||||
Class: rviz/Orbit
|
Class: rviz/Orbit
|
||||||
Distance: 1.9643197059631348
|
Distance: 2.0112123489379883
|
||||||
Enable Stereo Rendering:
|
Enable Stereo Rendering:
|
||||||
Stereo Eye Separation: 0.05999999865889549
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
Stereo Focal Distance: 1
|
Stereo Focal Distance: 1
|
||||||
Swap Stereo Eyes: false
|
Swap Stereo Eyes: false
|
||||||
Value: false
|
Value: false
|
||||||
Focal Point:
|
Focal Point:
|
||||||
X: 0.11843720823526382
|
X: 0.027046792209148407
|
||||||
Y: -0.025971120223402977
|
Y: -0.03490818291902542
|
||||||
Z: 0.012434899806976318
|
Z: -0.09952529519796371
|
||||||
Focal Shape Fixed Size: true
|
Focal Shape Fixed Size: true
|
||||||
Focal Shape Size: 0.05000000074505806
|
Focal Shape Size: 0.05000000074505806
|
||||||
Invert Z Axis: false
|
Invert Z Axis: false
|
||||||
Name: Current View
|
Name: Current View
|
||||||
Near Clip Distance: 0.009999999776482582
|
Near Clip Distance: 0.009999999776482582
|
||||||
Pitch: 0.3447958827018738
|
Pitch: 0.6247956156730652
|
||||||
Target Frame: <Fixed Frame>
|
Target Frame: <Fixed Frame>
|
||||||
Value: Orbit (rviz)
|
Value: Orbit (rviz)
|
||||||
Yaw: 3.9354026317596436
|
Yaw: 3.785417318344116
|
||||||
Saved: ~
|
Saved: ~
|
||||||
Window Geometry:
|
Window Geometry:
|
||||||
Displays:
|
Displays:
|
||||||
|
|||||||
@@ -5,26 +5,25 @@
|
|||||||
|
|
||||||
<xacro:arg name="urdf_extras" default="empty.urdf" />
|
<xacro:arg name="urdf_extras" default="empty.urdf" />
|
||||||
|
|
||||||
<!-- Included URDF/XACRO Files -->
|
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type1.xacro" />
|
||||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel.xacro" />
|
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type2.xacro" />
|
||||||
|
|
||||||
|
<!-- Variables -->
|
||||||
<xacro:property name="M_PI" value="3.14159"/>
|
<xacro:property name="M_PI" value="3.14159"/>
|
||||||
|
|
||||||
<!-- Base Size -->
|
<!-- Vehicle Geometries -->
|
||||||
<xacro:property name="base_x_size" value="0.9250000" />
|
<xacro:property name="base_x_size" value="0.9250000" />
|
||||||
<xacro:property name="base_y_size" value="0.380000" />
|
<xacro:property name="base_y_size" value="0.380000" />
|
||||||
<xacro:property name="base_z_size" value="0.210000" />
|
<xacro:property name="base_z_size" value="0.210000" />
|
||||||
|
|
||||||
<!-- Wheel Mounting Positions -->
|
|
||||||
<xacro:property name="wheelbase" value="0.498" />
|
<xacro:property name="wheelbase" value="0.498" />
|
||||||
<xacro:property name="track" value="0.58306" />
|
<xacro:property name="track" value="0.58306" />
|
||||||
<xacro:property name="wheel_vertical_offset" value="-0.0702" />
|
<xacro:property name="wheel_vertical_offset" value="-0.0702" />
|
||||||
|
|
||||||
<!-- Wheel Properties -->
|
|
||||||
<xacro:property name="wheel_length" value="1.1653e-01" />
|
<xacro:property name="wheel_length" value="1.1653e-01" />
|
||||||
<xacro:property name="wheel_radius" value="1.6459e-01" />
|
<xacro:property name="wheel_radius" value="1.6459e-01" />
|
||||||
|
|
||||||
<!-- Base link is the center of the robot's bottom plate -->
|
<!-- Base link -->
|
||||||
<link name="base_link">
|
<link name="base_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
@@ -46,7 +45,7 @@
|
|||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<!-- Base footprint is on the ground under the robot -->
|
<!-- Base footprint: base_link projected to the gound plane -->
|
||||||
<link name="base_footprint"/>
|
<link name="base_footprint"/>
|
||||||
|
|
||||||
<joint name="base_footprint_joint" type="fixed">
|
<joint name="base_footprint_joint" type="fixed">
|
||||||
@@ -55,7 +54,7 @@
|
|||||||
<child link="base_footprint" />
|
<child link="base_footprint" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<!-- Interial link stores the robot's inertial information -->
|
<!-- Interial link -->
|
||||||
<link name="inertial_link">
|
<link name="inertial_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="46.034" />
|
<mass value="46.034" />
|
||||||
@@ -70,6 +69,20 @@
|
|||||||
<child link="inertial_link" />
|
<child link="inertial_link" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
<!-- scout wheel macros -->
|
||||||
|
<xacro:scout_wheel_type2 wheel_prefix="front_left">
|
||||||
|
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
|
||||||
|
</xacro:scout_wheel_type2>
|
||||||
|
<xacro:scout_wheel_type1 wheel_prefix="front_right">
|
||||||
|
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
|
||||||
|
</xacro:scout_wheel_type1>
|
||||||
|
<xacro:scout_wheel_type1 wheel_prefix="rear_left">
|
||||||
|
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
|
||||||
|
</xacro:scout_wheel_type1>
|
||||||
|
<xacro:scout_wheel_type2 wheel_prefix="rear_right">
|
||||||
|
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
|
||||||
|
</xacro:scout_wheel_type2>
|
||||||
|
|
||||||
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
|
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
|
||||||
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
|
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
|
||||||
<!-- <link name="imu_link"/>
|
<!-- <link name="imu_link"/>
|
||||||
@@ -81,20 +94,6 @@
|
|||||||
<gazebo reference="imu_link">
|
<gazebo reference="imu_link">
|
||||||
</gazebo> -->
|
</gazebo> -->
|
||||||
|
|
||||||
<!-- scout wheel macros -->
|
|
||||||
<xacro:scout_wheel wheel_prefix="front_left">
|
|
||||||
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
|
|
||||||
</xacro:scout_wheel>
|
|
||||||
<xacro:scout_wheel wheel_prefix="front_right">
|
|
||||||
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
|
|
||||||
</xacro:scout_wheel>
|
|
||||||
<xacro:scout_wheel wheel_prefix="rear_left">
|
|
||||||
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
|
|
||||||
</xacro:scout_wheel>
|
|
||||||
<xacro:scout_wheel wheel_prefix="rear_right">
|
|
||||||
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
|
|
||||||
</xacro:scout_wheel>
|
|
||||||
|
|
||||||
<!-- <xacro:scout_decorate /> -->
|
<!-- <xacro:scout_decorate /> -->
|
||||||
|
|
||||||
<!-- <gazebo>
|
<!-- <gazebo>
|
||||||
|
|||||||
@@ -1,77 +0,0 @@
|
|||||||
<?xml version="1.0"?>
|
|
||||||
<!--
|
|
||||||
Software License Agreement (BSD)
|
|
||||||
|
|
||||||
\file scout_wheel.xacro (adapted from wheel.urdf.xacro in husky_description)
|
|
||||||
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
|
|
||||||
Ruixiang Du <ruixiang.du@westonrobot.com>
|
|
||||||
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
|
|
||||||
\copyright Copyright (c) 2020, Weston Robot Pte. Ltd., All rights reserved.
|
|
||||||
|
|
||||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
|
|
||||||
the following conditions are met:
|
|
||||||
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
|
|
||||||
following disclaimer.
|
|
||||||
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
|
|
||||||
following disclaimer in the documentation and/or other materials provided with the distribution.
|
|
||||||
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
|
|
||||||
products derived from this software without specific prior written permission.
|
|
||||||
|
|
||||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
|
|
||||||
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
|
||||||
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
|
|
||||||
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
|
|
||||||
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
|
||||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
-->
|
|
||||||
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_wheel">
|
|
||||||
|
|
||||||
<xacro:macro name="scout_wheel" params="wheel_prefix *joint_pose">
|
|
||||||
<link name="${wheel_prefix}_wheel_link">
|
|
||||||
<inertial>
|
|
||||||
<mass value="2.637" />
|
|
||||||
<origin xyz="0 0 0" />
|
|
||||||
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.04411" iyz="0" izz="0.02467" />
|
|
||||||
</inertial>
|
|
||||||
<visual>
|
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<mesh filename="package://scout_description/meshes/wheel_assembly.dae" />
|
|
||||||
</geometry>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
</link>
|
|
||||||
|
|
||||||
<!-- <gazebo reference="${wheel_prefix}_wheel_link">
|
|
||||||
<mu1 value="1.0"/>
|
|
||||||
<mu2 value="1.0"/>
|
|
||||||
<kp value="10000000.0" />
|
|
||||||
<kd value="1.0" />
|
|
||||||
<fdir1 value="1 0 0"/>
|
|
||||||
</gazebo> -->
|
|
||||||
|
|
||||||
<joint name="${wheel_prefix}_wheel" type="continuous">
|
|
||||||
<parent link="base_link"/>
|
|
||||||
<child link="${wheel_prefix}_wheel_link"/>
|
|
||||||
<xacro:insert_block name="joint_pose"/>
|
|
||||||
<axis xyz="0 1 0" rpy="0 0 0" />
|
|
||||||
</joint>
|
|
||||||
|
|
||||||
<!-- <transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
|
|
||||||
<type>transmission_interface/SimpleTransmission</type>
|
|
||||||
<actuator name="${wheel_prefix}_wheel_motor">
|
|
||||||
<mechanicalReduction>1</mechanicalReduction>
|
|
||||||
</actuator>
|
|
||||||
<joint name="${wheel_prefix}_wheel">
|
|
||||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
||||||
</joint>
|
|
||||||
</transmission> -->
|
|
||||||
|
|
||||||
</xacro:macro>
|
|
||||||
</robot>
|
|
||||||
Reference in New Issue
Block a user