-
-
Save hdd-robot/28f128aa1ee8025fb3934cfe85701937 to your computer and use it in GitHub Desktop.
correct files
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
vica_robot_controller: | |
type : "diff_drive_controller/DiffDriveController" | |
left_wheel : 'l_wheel_joint' | |
right_wheel : 'r_wheel_joint' | |
pid: {p: 100.0, i: 0.01, d: 10.0} | |
publish_rate: 100.0 # default: 50 | |
pose_covariance_diagonal : [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] | |
twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] | |
# Wheel separation and diameter. These are both optional. | |
# diff_drive_controller will attempt to read either one or both from the | |
# URDF if not specified as a parameter | |
wheel_separation : 0.28 | |
wheel_radius : 0.03 | |
# Wheel separation and radius multipliers | |
wheel_separation_multiplier: 1.0 # default: 1.0 | |
wheel_radius_multiplier : 1.0 # default: 1.0 | |
# Velocity commands timeout [s], default 0.5 | |
cmd_vel_timeout: 0.5 | |
# Base frame_id | |
base_frame_id: base_link #default: base_link | |
# Velocity and acceleration limits | |
# Whenever a min_* is unspecified, default to -max_* | |
linear: | |
x: | |
has_velocity_limits : true | |
max_velocity : 0.2 # m/s | |
min_velocity : -0.2 # m/s | |
has_acceleration_limits: true | |
max_acceleration : 0.05 # m/s^2 | |
min_acceleration : -0.05 # m/s^2 | |
angular: | |
z: | |
has_velocity_limits : true | |
max_velocity : 0.3 # rad/s | |
has_acceleration_limits: true | |
max_acceleration : 0.1 # rad/s^2 | |
joint_read_state_controller: | |
type: joint_state_controller/JointStateController | |
publish_rate: 100.0 | |
#Publish to TF directly or not | |
enable_odom_tf: true | |
#Name of frame to publish odometry in | |
odom_frame_id: odom | |
# Publish the velocity command to be executed. | |
# It is to monitor the effect of limiters on the controller input. | |
publish_cmd: true | |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<robot name="ubot" xmlns:xacro="http://www.ros.org/wiki/xacro"> | |
<xacro:include | |
filename="$(find vica_robot)/urdf/robot.gazebo" /> | |
<xacro:include | |
filename="$(find vica_robot)/urdf/materials.xacro" /> | |
<xacro:include | |
filename="$(find vica_robot)/urdf/macros.xacro" /> | |
<robotBaseFrame>base_link</robotBaseFrame> | |
<link name="base_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0.01" /> | |
<geometry> | |
<mesh scale=".0010 .0010 .0010" | |
filename="package://vica_robot/meshes/base.stl" /> | |
</geometry> | |
<material name="Yellow"> | |
<color rgba="1 1 0 1" /> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0.01" /> | |
<geometry> | |
<mesh scale=".0010 .0010 .0010" | |
filename="package://vica_robot/meshes/base.stl" /> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="5" /> | |
<origin xyz="0 0 0" rpy="0 0 0" /> | |
<inertia ixx="0.88" ixy="0" ixz="0" | |
iyy="0.88" iyz="0" | |
izz="0.88" /> | |
</inertial> | |
</link> | |
<!-- Roue libre devant --> | |
<link name="caster_front_link"> | |
<visual> | |
<origin xyz="0.135 0 0.0325" rpy="0 0 0" /> | |
<geometry> | |
<sphere radius="0.03" /> | |
</geometry> | |
</visual> | |
<collision name='caster_front_collision'> | |
<origin xyz="0.135 0 0.0325" rpy="0 0 0" /> | |
<geometry> | |
<sphere radius="0.03" /> | |
</geometry> | |
<surface> | |
<friction> | |
<ode> | |
<mu>0.01</mu> | |
<mu2>0.01</mu2> | |
<fdir1> 0 0 0</fdir1> | |
<slip1>1.0</slip1> | |
<slip2>1.0</slip2> | |
</ode> | |
</friction> | |
<bounce> | |
<restitution_coefficient>0</restitution_coefficient> | |
<threshold>100000</threshold> | |
</bounce> | |
<contact> | |
<ode> | |
<soft_cfm>0</soft_cfm> | |
<soft_erp>0.2</soft_erp> | |
<kp>1.0</kp> | |
<kd>1.0</kd> | |
<max_vel>1.0</max_vel> | |
<min_depth>0.001</min_depth> | |
</ode> | |
</contact> | |
</surface> | |
</collision> | |
<inertial> | |
<mass value="0.01" /> | |
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | |
iyy="0.001" iyz="0.0" | |
izz="0.001" /> | |
</inertial> | |
</link> | |
<joint name="caster_front_join" type="fixed"> | |
<parent link="base_link" /> | |
<child link="caster_front_link" /> | |
<origin xyz="0 0 0.0001" rpy="0 0 0" /> | |
</joint> | |
<!-- Fin Roue libre devant --> | |
<!-- Roue libre arriere --> | |
<link name="caster_back_link"> | |
<visual> | |
<origin xyz="-0.135 0 0.0325" rpy="0 0 0" /> | |
<geometry> | |
<sphere radius="0.03" /> | |
</geometry> | |
</visual> | |
<collision name='caster_back_collision'> | |
<origin xyz="-0.135 0 0.0325" rpy="0 0 0" /> | |
<geometry> | |
<sphere radius="0.03" /> | |
</geometry> | |
<surface> | |
<friction> | |
<ode> | |
<mu>0.01</mu> | |
<mu2>0.01</mu2> | |
<fdir1> 0 0 0</fdir1> | |
<slip1>1.0</slip1> | |
<slip2>1.0</slip2> | |
</ode> | |
</friction> | |
<bounce> | |
<restitution_coefficient>0</restitution_coefficient> | |
<threshold>100000</threshold> | |
</bounce> | |
<contact> | |
<ode> | |
<soft_cfm>0</soft_cfm> | |
<soft_erp>0.2</soft_erp> | |
<kp>1.0</kp> | |
<kd>1.0</kd> | |
<max_vel>1.0</max_vel> | |
<min_depth>0.001</min_depth> | |
</ode> | |
</contact> | |
</surface> | |
</collision> | |
<inertial> | |
<mass value="0.01"/> | |
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | |
iyy="0.001" iyz="0.0" | |
izz="0.001" /> | |
</inertial> | |
</link> | |
<joint name="caster_back_join" type="fixed"> | |
<parent link="base_link" /> | |
<child link="caster_back_link" /> | |
<origin xyz="0 0 0.0001" rpy="0 0 0" /> | |
</joint> | |
<!-- Fin Roue libre arriere --> | |
<link name="r_wheel"> | |
<visual> | |
<origin rpy="0 1.57079632679 0" xyz="0 0 0" /> | |
<geometry> | |
<!-- <mesh scale=".0010 .0010 .0010" filename="package://vica_robot/meshes/rwheel.stl" | |
/> --> | |
<cylinder length="0.025" radius="0.03" /> | |
</geometry> | |
<material name="Blue"> | |
<color rgba="0 1 1 1" /> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 1.57079632679 0" xyz="0 0 0" /> | |
<geometry> | |
<!-- <mesh scale=".0010 .0010 .0010" filename="package://vica_robot/meshes/rwheel.stl" | |
/> --> | |
<cylinder length="0.025" radius="0.03" /> | |
</geometry> | |
<surface> | |
<friction> | |
<ode> | |
<mu>1.0</mu> | |
<mu2>1.0</mu2> | |
<slip1>0.0</slip1> | |
<slip2>0.0</slip2> | |
</ode> | |
</friction> | |
<contact> | |
<ode> | |
</ode> | |
</contact> | |
</surface> | |
</collision> | |
<inertial> | |
<mass value="5" /> | |
<cylinder_inertia m="5" r="0.1" h="0.05" /> | |
<inertia ixx="0.89" ixy="0" ixz="0" iyy="1.0" iyz="0" | |
izz="0.88" /> | |
</inertial> | |
</link> | |
<joint name="r_wheel_joint" type="continuous"> | |
<parent link="base_link" /> | |
<child link="r_wheel" /> | |
<origin xyz="0 -0.15 0.0325" rpy="0 0 1.57079632679" /> | |
</joint> | |
<transmission name="r_wheel_transmission"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="r_wheel_joint"> | |
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="r_wheel_actuator"> | |
<mechanicalReduction>7</mechanicalReduction> | |
<hardwareInterface>VelocityJointInterface</hardwareInterface> | |
</actuator> | |
</transmission> | |
<link name="l_wheel"> | |
<visual> | |
<origin rpy="0 1.57079632679 0" xyz="0 0 0" /> | |
<geometry> | |
<cylinder length="0.025" radius="0.03" /> | |
</geometry> | |
<material name="Blue"> | |
<color rgba="0 1 1 1" /> | |
</material> | |
</visual> | |
<collision> | |
<origin rpy="0 1.57079632679 0" xyz="0 0 0" /> | |
<geometry> | |
<cylinder length="0.025" radius="0.03" /> | |
</geometry> | |
<surface> | |
<friction> | |
<ode> | |
<mu>1.0</mu> | |
<mu2>1.0</mu2> | |
<slip1>0</slip1> | |
<slip2>0</slip2> | |
</ode> | |
</friction> | |
<contact> | |
<ode> | |
</ode> | |
</contact> | |
</surface> | |
</collision> | |
<inertial> | |
<mass value="0.300" /> | |
<cylinder_inertia m="5" r="0.1" h="0.05" /> | |
<inertia ixx="0.88" ixy="0" ixz="0" iyy="1.0" iyz="0" | |
izz="0.88" /> | |
</inertial> | |
</link> | |
<joint name="l_wheel_joint" type="continuous"> | |
<parent link="base_link" /> | |
<child link="l_wheel" /> | |
<origin xyz="0 0.15 0.0325" rpy="0 0 1.57079632679" /> | |
</joint> | |
<transmission name="l_wheel_transmission"> | |
<type>transmission_interface/SimpleTransmission</type> | |
<joint name="l_wheel_joint"> | |
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> | |
</joint> | |
<actuator name="l_wheel_actuator"> | |
<mechanicalReduction>7</mechanicalReduction> | |
<hardwareInterface>VelocityJointInterface</hardwareInterface> | |
</actuator> | |
</transmission> | |
<link name="kinect"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0" /> | |
<geometry> | |
<mesh scale=".0010 .0010 .0010" | |
filename="package://vica_robot/meshes/kinect.stl" /> | |
</geometry> | |
<material name="Red"> | |
<color rgba="1 0 0 1" /> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh scale=".0010 .0010 .0010" | |
filename="package://vica_robot/meshes/kinect.stl" /> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.681" /> | |
<inertia ixx="0.89" ixy="0" ixz="0" iyy="1.0" iyz="0" | |
izz="0.89" /> | |
</inertial> | |
</link> | |
<link name="rplidar"> | |
<visual> | |
<origin rpy="1.57079632679 0 0" xyz="0 0 -0.04" /> | |
<geometry> | |
<mesh scale=".0010 .0010 .0010" | |
filename="package://vica_robot/meshes/rplidar.stl" /> | |
</geometry> | |
<material name="Red"> | |
<color rgba="1 0 0 1" /> | |
</material> | |
</visual> | |
<collision> | |
<geometry> | |
<mesh scale=".0010 .0010 .0010" | |
filename="package://vica_robot/meshes/rplidar.stl" /> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.681" /> | |
<inertia ixx="0.89" ixy="0" ixz="0" iyy="1.0" iyz="0" | |
izz="0.89" /> | |
</inertial> | |
</link> | |
<joint name="kinect_joint" type="fixed"> | |
<parent link="base_link" /> | |
<child link="kinect" /> | |
<origin xyz="0.055 -0.02 0.147" rpy="0 0 0" /> | |
</joint> | |
<joint name="rplidar_joint" type="fixed"> | |
<parent link="base_link" /> | |
<child link="rplidar" /> | |
<origin xyz="-0.06 0.033 0.28" rpy="0 0 0" /> | |
</joint> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment