mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 03:15:01 +08:00
added scout_description back
This commit is contained in:
13
scout_description/CMakeLists.txt
Normal file
13
scout_description/CMakeLists.txt
Normal file
@@ -0,0 +1,13 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(scout_description)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS roslaunch)
|
||||
|
||||
catkin_package()
|
||||
|
||||
# roslaunch_add_file_check(launch)
|
||||
|
||||
install(
|
||||
DIRECTORY launch meshes urdf
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||
)
|
||||
8
scout_description/launch/description.launch
Normal file
8
scout_description/launch/description.launch
Normal file
@@ -0,0 +1,8 @@
|
||||
<launch>
|
||||
<arg name = "model_xacro" default = "$(find scout_description)/urdf/scout_v2.xacro" />
|
||||
<arg name="model" />
|
||||
|
||||
<param name="robot_description" command="$(find xacro)/xacro $(arg model_xacro)"/>
|
||||
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
|
||||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
|
||||
</launch>
|
||||
442
scout_description/meshes/base_link.dae
Normal file
442
scout_description/meshes/base_link.dae
Normal file
File diff suppressed because one or more lines are too long
15
scout_description/meshes/base_link_full.dae
Normal file
15
scout_description/meshes/base_link_full.dae
Normal file
@@ -0,0 +1,15 @@
|
||||
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
|
||||
<asset>
|
||||
<contributor />
|
||||
<created>2020-03-27T18:56:12.965296</created>
|
||||
<modified>2020-03-27T18:56:12.965305</modified>
|
||||
<unit name="meter" meter="1.0" />
|
||||
<up_axis>Z_UP</up_axis>
|
||||
</asset>
|
||||
<library_visual_scenes>
|
||||
<visual_scene id="myscene" />
|
||||
</library_visual_scenes>
|
||||
<scene>
|
||||
<instance_visual_scene url="#myscene" />
|
||||
</scene>
|
||||
</COLLADA>
|
||||
253
scout_description/meshes/hokuyo.dae
Executable file
253
scout_description/meshes/hokuyo.dae
Executable file
File diff suppressed because one or more lines are too long
274
scout_description/meshes/wheel_type1.dae
Normal file
274
scout_description/meshes/wheel_type1.dae
Normal file
File diff suppressed because one or more lines are too long
274
scout_description/meshes/wheel_type2.dae
Normal file
274
scout_description/meshes/wheel_type2.dae
Normal file
File diff suppressed because one or more lines are too long
30
scout_description/package.xml
Normal file
30
scout_description/package.xml
Normal file
@@ -0,0 +1,30 @@
|
||||
<?xml version="1.0"?>
|
||||
<package>
|
||||
<name>scout_description</name>
|
||||
<version>0.4.2</version>
|
||||
<description>AgileX Scout Husky URDF description</description>
|
||||
|
||||
<author email="rgariepy@clearpathrobotics.com">Ryan Gariepy</author>
|
||||
<author email="pmukherj@clearpathrobotics.com">Prasenjit Mukherjee</author>
|
||||
<author email="mpurvis@clearpathrobotics.com">Mike Purvis</author>
|
||||
<author email="paul@bovbel.com">Paul Bovbel</author>
|
||||
<author email="dash@clearpathrobotics.com">Devon Ash</author>
|
||||
|
||||
<maintainer email="paul@bovbel.com">Paul Bovbel</maintainer>
|
||||
<maintainer email="tbaltovski@clearpathrobotics.com">Tony Baltovski</maintainer>
|
||||
|
||||
<url type="website">http://ros.org/wiki/scout_description</url>
|
||||
<url type="bugtracker">https://github.com/husky/husky/issues</url>
|
||||
<url type="repository">https://github.com/husky/husky</url>
|
||||
|
||||
<license>BSD</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>roslaunch</build_depend>
|
||||
<run_depend>urdf</run_depend>
|
||||
<run_depend>xacro</run_depend>
|
||||
<run_depend>lms1xx</run_depend>
|
||||
|
||||
<export>
|
||||
</export>
|
||||
</package>
|
||||
31
scout_description/urdf/onboard_sensors.urdf
Normal file
31
scout_description/urdf/onboard_sensors.urdf
Normal file
@@ -0,0 +1,31 @@
|
||||
<robot>
|
||||
<joint name="hokuyo_joint" type="fixed">
|
||||
<origin xyz="0.26 0 0.3" rpy="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<axis xyz="0 1 0" />
|
||||
<child link="hokuyo_link"/>
|
||||
</joint>
|
||||
|
||||
<!-- Hokuyo Laser -->
|
||||
<link name="hokuyo_link">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.1 0.1 0.1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/hokuyo.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<mass value="1e-5" />
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
|
||||
</inertial>
|
||||
</link>
|
||||
</robot>
|
||||
111
scout_description/urdf/scout_v2.gazebo
Normal file
111
scout_description/urdf/scout_v2.gazebo
Normal file
@@ -0,0 +1,111 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<!--
|
||||
Reference:
|
||||
[1] https://answers.ros.org/question/246914/four-wheeled-skid-steering-in-gazebo-and-ros-using-gazebo-ros-control/
|
||||
[2] https://answers.ros.org/question/10119/gazebo-controller-for-skid-steering/
|
||||
[3] https://answers.ros.org/question/9640/rotation-error-in-gazebo-simulation/
|
||||
[4] https://www.youtube.com/watch?v=fuRAv6PDwdw
|
||||
-->
|
||||
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel.gazebo" />
|
||||
|
||||
<!-- Additional definitions for simulation -->
|
||||
<!-- <gazebo reference="base_link">
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo> -->
|
||||
|
||||
<!-- Actuator configurations -->
|
||||
<xacro:scout_wheel_transmission wheel_prefix="front_right" />
|
||||
<xacro:scout_wheel_transmission wheel_prefix="front_left" />
|
||||
<xacro:scout_wheel_transmission wheel_prefix="rear_left" />
|
||||
<xacro:scout_wheel_transmission wheel_prefix="rear_right" />
|
||||
|
||||
<!-- Controller configurations -->
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>$(arg robot_namespace)</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- kp spring constant, kd damping constant -->
|
||||
<gazebo>
|
||||
<mu1 value="1.0"/>
|
||||
<mu2 value="1.0"/>
|
||||
<kp value="10000000.0" />
|
||||
<kd value="1.0" />
|
||||
<fdir1 value="1 0 0"/>
|
||||
<minDepth value="0.001" />
|
||||
<maxContacts value="64"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- hokuyo -->
|
||||
<gazebo reference="hokuyo_link">
|
||||
<sensor type="ray" name="head_hokuyo_sensor">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<visualize>false</visualize>
|
||||
<update_rate>40</update_rate>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>720</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-1.570796</min_angle>
|
||||
<max_angle>1.570796</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.10</min>
|
||||
<max>30.0</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<!-- Noise parameters based on published spec for Hokuyo laser
|
||||
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
|
||||
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
|
||||
reading. -->
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.01</stddev>
|
||||
</noise>
|
||||
</ray>
|
||||
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
||||
<topicName>/scan</topicName>
|
||||
<frameName>hokuyo_link</frameName>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
<!-- <gazebo>
|
||||
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
|
||||
<updateRate>100.0</updateRate>
|
||||
<robotNamespace></robotNamespace>
|
||||
<leftFrontJoint>front_left_wheel</leftFrontJoint>
|
||||
<rightFrontJoint>front_right_wheel</rightFrontJoint>
|
||||
<leftRearJoint>rear_left_wheel</leftRearJoint>
|
||||
<rightRearJoint>rear_right_wheel</rightRearJoint>
|
||||
<wheelSeparation>4</wheelSeparation>
|
||||
<wheelDiameter>0.32918</wheelDiameter>
|
||||
<robotBaseFrame>base_link</robotBaseFrame>
|
||||
<torque>1000</torque>
|
||||
<commandTopic>cmd_vel</commandTopic>
|
||||
<broadcastTF>true</broadcastTF>
|
||||
<odometryTopic>odom</odometryTopic>
|
||||
<odometryFrame>odom</odometryFrame>
|
||||
<covariance_x>0.000100</covariance_x>
|
||||
<covariance_y>0.000100</covariance_y>
|
||||
<covariance_yaw>0.010000</covariance_yaw>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
|
||||
<!-- <gazebo>
|
||||
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
|
||||
<commandTopic>cmd_vel</commandTopic>
|
||||
<odometryTopic>odom</odometryTopic>
|
||||
<odometryFrame>odom</odometryFrame>
|
||||
<odometryRate>20.0</odometryRate>
|
||||
<robotBaseFrame>base_footprint</robotBaseFrame>
|
||||
</plugin>
|
||||
</gazebo> -->
|
||||
</robot>
|
||||
137
scout_description/urdf/scout_v2.urdf
Normal file
137
scout_description/urdf/scout_v2.urdf
Normal file
@@ -0,0 +1,137 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from scout_description/urdf/scout_v2_webots.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="scout_v2">
|
||||
<!-- Base link -->
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/base_link.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.008"/>
|
||||
<geometry>
|
||||
<box size="0.925 0.38 0.21"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.035"/>
|
||||
<geometry>
|
||||
<box size="0.154166666667 0.627 0.07"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="40"/>
|
||||
<origin xyz="0.0 0.0 0.0"/>
|
||||
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="front_right_wheel_link">
|
||||
<inertial>
|
||||
<mass value="3"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/wheel_type1.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.11653" radius="0.16459"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="front_right_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="front_right_wheel_link"/>
|
||||
<origin rpy="3.14 0 0" xyz="0.249 -0.29153 -0.0702"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<link name="front_left_wheel_link">
|
||||
<inertial>
|
||||
<mass value="3"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/wheel_type2.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.11653" radius="0.16459"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="front_left_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="front_left_wheel_link"/>
|
||||
<origin rpy="0 0 0" xyz="0.249 0.29153 -0.0702"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<link name="rear_left_wheel_link">
|
||||
<inertial>
|
||||
<mass value="3"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/wheel_type1.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.11653" radius="0.16459"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rear_left_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="rear_left_wheel_link"/>
|
||||
<origin rpy="0 0 0" xyz="-0.249 0.29153 -0.0702"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<link name="rear_right_wheel_link">
|
||||
<inertial>
|
||||
<mass value="3"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/wheel_type2.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.11653" radius="0.16459"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rear_right_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="rear_right_wheel_link"/>
|
||||
<origin rpy="3.14 0 0" xyz="-0.249 -0.29153 -0.0702"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<!-- Additional definitions -->
|
||||
<!-- <xacro:include filename="$(arg urdf_extras)" /> -->
|
||||
<!-- Gazebo definitions -->
|
||||
<!-- <xacro:include filename="$(find scout_description)/urdf/scout_v2.gazebo" /> -->
|
||||
</robot>
|
||||
94
scout_description/urdf/scout_v2.xacro
Normal file
94
scout_description/urdf/scout_v2.xacro
Normal file
@@ -0,0 +1,94 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="scout_v2"
|
||||
xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<xacro:arg name="robot_namespace" default="/" />
|
||||
<xacro:arg name="onboard_sensors" default="false" />
|
||||
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type1.xacro" />
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type2.xacro" />
|
||||
|
||||
<!-- Variables -->
|
||||
<xacro:property name="M_PI" value="3.14159"/>
|
||||
|
||||
<!-- Vehicle Geometries -->
|
||||
<xacro:property name="base_x_size" value="0.9250000" />
|
||||
<xacro:property name="base_y_size" value="0.380000" />
|
||||
<xacro:property name="base_z_size" value="0.210000" />
|
||||
|
||||
<xacro:property name="wheelbase" value="0.498" />
|
||||
<xacro:property name="track" value="0.58306" />
|
||||
<xacro:property name="wheel_vertical_offset" value="-0.0702" />
|
||||
|
||||
<xacro:property name="wheel_length" value="1.1653e-01" />
|
||||
<xacro:property name="wheel_radius" value="1.6459e-01" />
|
||||
|
||||
<!-- Base link -->
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/base_link.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0.008" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="${base_x_size} ${base_y_size} ${base_z_size}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision>
|
||||
<origin xyz="0 0 ${base_z_size/6}" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<box size="${base_x_size/6} ${base_y_size*1.65} ${base_z_size/3}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="base_footprint"/>
|
||||
|
||||
<joint name="base_footprint_joint" type="fixed">
|
||||
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="base_footprint" />
|
||||
</joint>
|
||||
|
||||
<link name="inertial_link">
|
||||
<inertial>
|
||||
<mass value="40" />
|
||||
<origin xyz="0.0 0.0 0.0" />
|
||||
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="inertial_joint" type="fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="inertial_link" />
|
||||
</joint>
|
||||
|
||||
<!-- Scout wheel macros -->
|
||||
<!-- wheel labeled from 0 to 3, conter-clockwise, starting from front right wheel -->
|
||||
<!-- motor 1 and 2 (left side) are mechanically installed in a reversed direction -->
|
||||
<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_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="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>
|
||||
|
||||
<!-- Onboard sensors -->
|
||||
<xacro:if value="$(arg onboard_sensors)">
|
||||
<xacro:include filename="$(find scout_description)/urdf/onboard_sensors.urdf" />
|
||||
</xacro:if>
|
||||
|
||||
<!-- Gazebo definitions -->
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_v2.gazebo" />
|
||||
</robot>
|
||||
42
scout_description/urdf/scout_wheel.gazebo
Normal file
42
scout_description/urdf/scout_wheel.gazebo
Normal file
@@ -0,0 +1,42 @@
|
||||
<?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_transmission" params="wheel_prefix">
|
||||
<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>
|
||||
59
scout_description/urdf/scout_wheel_type1.xacro
Normal file
59
scout_description/urdf/scout_wheel_type1.xacro
Normal file
@@ -0,0 +1,59 @@
|
||||
<?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_type1" params="wheel_prefix *joint_pose">
|
||||
<link name="${wheel_prefix}_wheel_link">
|
||||
<inertial>
|
||||
<mass value="3" />
|
||||
<origin xyz="0 0 0" />
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/wheel_type1.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>
|
||||
|
||||
<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>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
59
scout_description/urdf/scout_wheel_type2.xacro
Normal file
59
scout_description/urdf/scout_wheel_type2.xacro
Normal file
@@ -0,0 +1,59 @@
|
||||
<?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_type2" params="wheel_prefix *joint_pose">
|
||||
<link name="${wheel_prefix}_wheel_link">
|
||||
<inertial>
|
||||
<mass value="3" />
|
||||
<origin xyz="0 0 0" />
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/wheel_type2.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>
|
||||
|
||||
<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>
|
||||
</xacro:macro>
|
||||
|
||||
</robot>
|
||||
Reference in New Issue
Block a user