Last active
August 29, 2015 14:19
-
-
Save marjinal1st/5959ff0902c69a6fa702 to your computer and use it in GitHub Desktop.
Robot
This file contains hidden or 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" ?> | |
<!-- =================================================================================== --> | |
<!-- | This document was autogenerated by xacro from robot1_base_02.xacro | --> | |
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> | |
<!-- =================================================================================== --> | |
<robot name="robot1_xacro" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://www.ros.org/wiki/xacro"> | |
<link name="base_footprint"> | |
<visual> | |
<geometry> | |
<box size="0.001 0.001 0.001"/> | |
</geometry> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
</visual> | |
<inertial> | |
<mass value="0.0001"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
</link> | |
<gazebo reference="base_footprint"> | |
<material>Gazebo/Green</material> | |
<turnGravityOff>false</turnGravityOff> | |
</gazebo> | |
<joint name="base_footprint_joint" type="fixed"> | |
<origin xyz="0 0 0"/> | |
<parent link="base_footprint"/> | |
<child link="base_link"/> | |
</joint> | |
<link name="base_link"> | |
<visual> | |
<geometry> | |
<box size="0.2 .3 .1"/> | |
</geometry> | |
<origin rpy="0 0 1.54" xyz="0 0 0.05"/> | |
</visual> | |
<collision> | |
<geometry> | |
<box size="0.2 .3 0.1"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="10"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
</link> | |
<gazebo reference="base_link"> | |
<material value="Gazebo/Red" /> | |
</gazebo> | |
<link name="wheel_1"> | |
<visual> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
<!-- <origin rpy="0 1.5 0" xyz="0.1 0.1 0"/> --> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<material name="Black" /> | |
</visual> | |
<collision> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="1"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
</link> | |
<gazebo reference="wheel_1"> | |
<material value="Gazebo/Black" /> | |
</gazebo> | |
<link name="wheel_2"> | |
<visual> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
<!-- <origin rpy="0 1.5 0" xyz="-0.1 0.1 0"/> --> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<material name="black"/> | |
</visual> | |
<collision> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="1"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
</link> | |
<gazebo reference="wheel_2"> | |
<material value="Gazebo/Black" /> | |
</gazebo> | |
<link name="wheel_3"> | |
<visual> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
<!-- <origin rpy="0 1.5 0" xyz="0.1 -0.1 0"/> --> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<material name="black"/> | |
</visual> | |
<collision> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="1"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
</link> | |
<gazebo reference="wheel_3"> | |
<material value="Gazebo/Black" /> | |
</gazebo> | |
<link name="wheel_4"> | |
<visual> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
<!-- <origin rpy="0 1.5 0" xyz="-0.1 -0.1 0"/> --> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<material name="black"/> | |
</visual> | |
<collision> | |
<geometry> | |
<cylinder length="0.05" radius="0.05"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="1"/> | |
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> | |
</inertial> | |
</link> | |
<gazebo reference="wheel_4"> | |
<material value="Gazebo/Black" /> | |
</gazebo> | |
<joint name="base_to_wheel1" type="continuous"> | |
<parent link="base_link"/> | |
<child link="wheel_1"/> | |
<origin rpy="1.5707 0 0" xyz="0.1 0.15 0"/> | |
<axis xyz="0 0 1"/> | |
</joint> | |
<joint name="base_to_wheel2" type="continuous"> | |
<axis xyz="0 0 1"/> | |
<anchor xyz="0 0 0"/> | |
<limit effort="100" velocity="100"/> | |
<parent link="base_link"/> | |
<child link="wheel_2"/> | |
<origin rpy="1.5707 0 0" xyz="-0.1 0.15 0"/> | |
</joint> | |
<joint name="base_to_wheel3" type="continuous"> | |
<parent link="base_link"/> | |
<axis xyz="0 0 1"/> | |
<child link="wheel_3"/> | |
<origin rpy="1.5707 0 0" xyz="0.1 -0.15 0"/> | |
</joint> | |
<joint name="base_to_wheel4" type="continuous"> | |
<parent link="base_link"/> | |
<axis xyz="0 0 1"/> | |
<child link="wheel_4"/> | |
<origin rpy="1.5707 0 0" xyz="-0.1 -0.15 0"/> | |
</joint> | |
<!-- Camera --> | |
<joint name="camera_joint" type="fixed"> | |
<axis xyz="0 1 0" /> | |
<origin xyz=".15 0 .18" rpy="0 0 0"/> | |
<parent link="base_link"/> | |
<child link="camera_link"/> | |
</joint> | |
<link name="camera_link"> | |
<collision> | |
<origin xyz="0 0 0" rpy="0 0 0"/> | |
<geometry> | |
<box size=".05 .05 .05"/> | |
</geometry> | |
</collision> | |
<visual> | |
<origin xyz="0 0 0" rpy="0 0 0"/> | |
<geometry> | |
<box size=".05 .05 .05"/> | |
</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> | |
<gazebo reference="camera_link"> | |
<material value="Gazebo/Blue" /> | |
</gazebo> | |
<!-- Camera Gazebo --> | |
<gazebo reference="camera_link"> | |
<sensor type="camera" name="camera1"> | |
<update_rate>30.0</update_rate> | |
<camera name="head"> | |
<horizontal_fov>1.3962634</horizontal_fov> | |
<image> | |
<width>800</width> | |
<height>600</height> | |
<format>R8G8B8</format> | |
</image> | |
<clip> | |
<near>0.02</near> | |
<far>300</far> | |
</clip> | |
<noise> | |
<type>gaussian</type> | |
<!-- Noise is sampled independently per pixel on each frame. | |
That pixel's noise value is added to each of its color | |
channels, which at that point lie in the range [0,1]. --> | |
<mean>0.0</mean> | |
<stddev>0.007</stddev> | |
</noise> | |
</camera> | |
<plugin name="camera_controller" filename="libgazebo_ros_camera.so"> | |
<alwaysOn>true</alwaysOn> | |
<updateRate>0.0</updateRate> | |
<cameraName>front_camera</cameraName> | |
<imageTopicName>image_raw</imageTopicName> | |
<cameraInfoTopicName>camera_info</cameraInfoTopicName> | |
<frameName>camera_link</frameName> | |
<hackBaseline>0.07</hackBaseline> | |
<distortionK1>0.0</distortionK1> | |
<distortionK2>0.0</distortionK2> | |
<distortionK3>0.0</distortionK3> | |
<distortionT1>0.0</distortionT1> | |
<distortionT2>0.0</distortionT2> | |
</plugin> | |
</sensor> | |
</gazebo> | |
<!-- Laser --> | |
<!-- Front Laser --> | |
<joint name="chassis_front_laser_joint" type="fixed"> | |
<axis xyz="0 0 1"/> | |
<origin rpy="0 0 0" xyz="0.18 0 0.06"/> | |
<parent link="base_link"/> | |
<child link="front_laser"/> | |
</joint> | |
<link name="front_laser"> | |
<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://bazebo/meshes/hokuyo.dae"/> | |
</geometry> | |
</visual> | |
<inertial> | |
<mass value="1e-5"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/> | |
</inertial> | |
</link> | |
<gazebo reference="front_laser"> | |
<sensor name="laser" type="ray"> | |
<pose>0 0 0 0 0 0</pose> | |
<ray> | |
<scan> | |
<horizontal> | |
<!-- The URG-04LX-UG01 has 683 steps with 0.35139 Degree resolution --> | |
<resolution>1</resolution> | |
<max_angle>1.0472</max_angle> | |
<min_angle>-1.0472</min_angle> | |
<samples>5</samples> | |
</horizontal> | |
</scan> | |
<range> | |
<min>0.08</min> | |
<max>5</max> | |
<resolution>0.01</resolution> | |
</range> | |
</ray> | |
<plugin filename="libgazebo_ros_laser.so" name="laser"> | |
<robotNamespace></robotNamespace> | |
<topicName>front_laser/scan</topicName> | |
<frameName>front_laser</frameName> | |
</plugin> | |
<!-- | |
<plugin name="laser" filename="libRayPlugin.so" /> | |
--> | |
<always_on>1</always_on> | |
<update_rate>30</update_rate> | |
<visualize>true</visualize> | |
</sensor> | |
</gazebo> | |
<!-- Differential Driver Eklentisi/> --> | |
<gazebo> | |
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller"> | |
<rosDebugLevel>Debug</rosDebugLevel> | |
<robotNamespace></robotNamespace> | |
<publishWheelTF>false</publishWheelTF> | |
<publishWheelJointState>true</publishWheelJointState> | |
<alwaysOn>false</alwaysOn> | |
<leftJoint>base_to_wheel4</leftJoint> | |
<rightJoint>base_to_wheel2</rightJoint> | |
<wheelSeparation>0.33</wheelSeparation> | |
<wheelDiameter>0.1</wheelDiameter> | |
<wheelTorque>5</wheelTorque> | |
<commandTopic>cmd_vel</commandTopic> | |
<odometryTopic>odom</odometryTopic> | |
<odometryFrame>odom</odometryFrame> | |
<odometrySource>world</odometrySource> | |
<robotBaseFrame>base_link</robotBaseFrame> | |
<updateRate>100.0</updateRate> | |
</plugin> | |
</gazebo> | |
</robot> |
This file contains hidden or 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
#!/usr/bin/env python | |
# -*- coding: utf-8 -*- | |
import rospy | |
from geometry_msgs.msg import Twist | |
def main(): | |
rospy.init_node("move_test", anonymous=False) | |
cmd_vel = rospy.Publisher("/rrbot/cmd_vel", Twist, queue_size=10) | |
r = rospy.Rate(10) | |
move_cmd = Twist() | |
move_cmd.linear.x = 0.2 | |
move_cmd.angular.z = 0.0 | |
while not rospy.is_shutdown(): | |
cmd_vel.publish(move_cmd) | |
r.sleep() | |
cmd_vel.publish(Twist()) | |
rospy.sleep(1) | |
if __name__ == "__main__": | |
main() |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment