Skip to content

Commit

Permalink
fix urdf
Browse files Browse the repository at this point in the history
  • Loading branch information
Garvit-32 committed Nov 23, 2020
1 parent 6748533 commit c2379f4
Show file tree
Hide file tree
Showing 5 changed files with 375 additions and 81 deletions.
14 changes: 7 additions & 7 deletions pkg_techfest_imc/launch/final.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,19 +4,19 @@
<include file = "$(find pkg_techfest_imc)/launch/gazebo.launch" />

<!-- <include file = "$(find pkg_techfest_imc)/launch/rviz.launch" /> -->

<!--node name="cmd_robot" pkg="pkg_techfest_imc" type="cmd_vel_robot.py"/-->

<!--node name="reading_laser" pkg="pkg_techfest_imc" type="node_follow_wall.py"/-->

<!--node name="node_maze_runner" pkg="pkg_techfest_imc" type="node_maze_runner.py"/-->

<!--node name="obstacle" pkg="pkg_techfest_imc" type="node_obstacle_avoidance.py"/-->

<node name="servo_cmd" pkg="pkg_techfest_imc" type="position_controller.py"/>

<!--node name="try" pkg="pkg_techfest_imc" type="trial.py"/-->

<node name="try" pkg="pkg_techfest_imc" type="trial.py"/>

</launch>
Empty file modified pkg_techfest_imc/scripts/position_controller.py
100644 → 100755
Empty file.
18 changes: 15 additions & 3 deletions pkg_techfest_imc/scripts/trial.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,18 @@
import math
import time


hz = 20 # Cycle Frequency
loop_index = 0 # Number of sampling cycles
loop_index_outer_corner = 0 # Loop index when the outer corner is detected
loop_index_inner_corner = 0 # Loop index when the inner corner is detected
# Limit to Laser sensor range in meters, all distances above this value are
inf = 10
# considered out of sensor range
wall_dist = 0.08 # Distance desired from the wall
max_speed = 0.3 # Maximum speed of the robot on meters/seconds
p = 15 # Proportional constant for controller
wall_dist = 0.08 # Distance desired from the wall
max_speed = 0.4 # Maximum speed of the robot on meters/seconds
# max_speed = 0.28 # Maximum speed of the robot on meters/seconds
p = 25 # Proportional constant for controller
d = 0 # Derivative constant for controller
# Proportional constant for angle controller (just simple P controller)
angle = 1
Expand Down Expand Up @@ -60,6 +62,7 @@
bool_inner_corner = 0

last_vel = [random.uniform(0.1, 0.3), random.uniform(-0.3, 0.3)]
# last_vel = [random.uniform(0.1, 0.5), random.uniform(-0.3, 0.3)]
wall_found = 0

# Robot state machines
Expand Down Expand Up @@ -106,6 +109,15 @@ def clbk_laser(msg):
'left': min(mean(msg.ranges[720:863]), inf),
'bleft': min(mean(msg.ranges[864:1007]), inf),
}
# regions_ = {
# 'bright': min(min(msg.ranges[0:143]), inf),
# 'right': min(min(msg.ranges[144:287]), inf),
# 'fright': min(min(msg.ranges[288:431]), inf),
# 'front': min(min(msg.ranges[432:575]), inf),
# 'fleft': min(min(msg.ranges[576:719]), inf),
# 'left': min(min(msg.ranges[720:863]), inf),
# 'bleft': min(min(msg.ranges[864:1007]), inf),
# }
# rospy.loginfo(regions_)

# Detection of Outer and Inner corner
Expand Down
143 changes: 72 additions & 71 deletions pkg_techfest_imc/urdf/micromouse_robot.urdf
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
<?xml version="1.0" ?>

<robot name="my_mm_robot" xmlns:xacro="https://www.ros.org/wiki/xacro" >

<robot name="my_mm_robot"
xmlns:xacro="https://www.ros.org/wiki/xacro">

<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
Expand All @@ -25,8 +26,8 @@
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>

</material>
<xacro:property name="Factor" value="0.7"/>
<gazebo reference="link_chassis">
<material>Gazebo/Orange</material>
</gazebo>
Expand All @@ -36,36 +37,36 @@
<gazebo reference="link_right_wheel">
<material>Gazebo/Black</material>
</gazebo>

<link name="link_chassis">
<!-- pose and inertial -->
<pose>0 0 0.1 0 0 0</pose>

<inertial>
<mass value="0.5"/>
<origin rpy="0 0 0" xyz="0 0.01 0"/>
<origin rpy="0 0 0" xyz="0 ${Factor*0.01} 0"/>
<inertia ixx="0.00022083" ixy="0" ixz="0" iyy="0.00022083" iyz="0" izz="0.00040833"/>
</inertial>

<collision name="link_chassis_collision">
<origin rpy="0 0 0" xyz="0 0 -0.005"/>
<geometry>
<box size="0.07 0.07 0.02"/>
<box size="${Factor*0.07} ${Factor*0.07} ${Factor*0.02}"/>
</geometry>
</collision>

<visual name="link_chassis_visual">
<origin rpy="0 0 0" xyz="0 0 -0.005"/>
<origin rpy="0 0 0" xyz="0 0 ${Factor*-0.005}"/>
<geometry>
<box size="0.06 0.06 0.02"/>
<box size="${Factor*0.06} ${Factor*0.06} ${Factor*0.02}"/>
</geometry>
</visual>

<!-- caster front -->
<collision name="caster_front_collision">
<origin rpy="0 0 0" xyz="0 -0.03 -0.015"/>
<origin rpy="0 0 0" xyz="0 ${Factor*(-0.03)} ${Factor*(-0.015)}"/>
<geometry>
<sphere radius="0.003"/>
<sphere radius="${Factor*0.003}"/>
</geometry>
<surface>
<friction>
Expand All @@ -78,103 +79,103 @@
</friction>
</surface>
</collision>

<visual name="castor_front_visual">
<origin rpy="0 0 0" xyz="0 -0.03 -0.015"/>
<origin rpy="0 0 0" xyz="0 ${Factor*(-0.01)} ${Factor*(-0.015)}"/>
<geometry>
<sphere radius="0.003"/>
<sphere radius="${Factor*0.005}"/>
</geometry>
</visual>
</link>
<!-- Create wheel right -->
<link name="link_right_wheel">
</link>

<!-- Create wheel right -->

<link name="link_right_wheel">
<inertial>
<mass value="0.2"/>
<origin rpy="0 1.5707 0" xyz="0 0 0"/>
<inertia ixx="2.3e-06" ixy="0" ixz="0" iyy="2.3e-06" iyz="0" izz="4.5e-06"/>
</inertial>

<collision name="link_right_wheel_collision">
<origin rpy="0 1.5707 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.007" radius="0.0175"/>
<cylinder length="${Factor*0.007}" radius="${Factor*0.0175}"/>
</geometry>
</collision>

<visual name="link_right_wheel_visual">
<origin rpy="0 1.5707 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.007" radius="0.0175"/>
</geometry>
<cylinder length="${Factor*0.007}" radius="${Factor*0.0175}"/>
</geometry>
</visual>

</link>

<!-- Joint for right wheel -->
<joint name="joint_right_wheel" type="continuous">
<origin rpy="0 0 0" xyz="-0.03 0.02 0"/>
<origin rpy="0 0 0" xyz="${Factor*(-0.03)} ${Factor*0.02} 0"/>
<child link="link_right_wheel" />
<parent link="link_chassis"/>
<axis rpy="0 0 0" xyz="1 0 0"/>
<axis rpy="0 0 0" xyz="${Factor*1} 0 0"/>
<limit effort="5" velocity="6"/>
<joint_properties damping="10000.0" friction="10000.0" />
</joint>
</joint>
<transmission name="right_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="right_wheel_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>7</mechanicalReduction>
</actuator>
<joint name="joint_right_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<type>transmission_interface/SimpleTransmission</type>
<actuator name="right_wheel_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>7</mechanicalReduction>
</actuator>
<joint name="joint_right_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>

<!-- Left Wheel link -->
<link name="link_left_wheel">

<link name="link_left_wheel">
<inertial>
<mass value="0.2"/>
<origin rpy="0 1.5707 0" xyz="0 0 0"/>
<inertia ixx="2.3e-06" ixy="0" ixz="0" iyy="2.3e-06" iyz="0" izz="4.5e-06"/>
</inertial>

<collision name="link_left_wheel_collision">
<origin rpy="0 1.5707 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.007" radius="0.0175"/>
<cylinder length="${Factor*0.007}" radius="${Factor*0.0175}"/>
</geometry>
</collision>

<visual name="link_left_wheel_visual">
<origin rpy="0 1.5707 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.007" radius="0.0175"/>
</geometry>
<cylinder length="${Factor*0.007}" radius="${Factor*0.0175}"/>
</geometry>
</visual>

</link>

<!-- Joint for right wheel -->
<joint name="joint_left_wheel" type="continuous">
<origin rpy="0 0 0" xyz="0.028 0.02 0"/>
<origin rpy="0 0 0" xyz="${Factor*0.028} ${Factor*0.02} 0"/>
<child link="link_left_wheel" />
<parent link="link_chassis"/>
<axis rpy="0 0 0" xyz="1 0 0"/>
<limit effort="5" velocity="6"/>
<joint_properties damping="10000.0" friction="10000.0" />
</joint>
</joint>
<transmission name="left_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="left_wheel_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>7</mechanicalReduction>
</actuator>
<joint name="joint_left_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<type>transmission_interface/SimpleTransmission</type>
<actuator name="left_wheel_motor">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>7</mechanicalReduction>
</actuator>
<joint name="joint_left_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>


Expand All @@ -184,8 +185,8 @@
<updateRate>20</updateRate>
<leftJoint>joint_left_wheel</leftJoint>
<rightJoint>joint_right_wheel</rightJoint>
<wheelSeparation>0.4</wheelSeparation>
<wheelDiameter>0.2</wheelDiameter>
<wheelSeparation>${Factor*0.35}</wheelSeparation>
<wheelDiameter>${Factor*0.17}</wheelDiameter>
<torque>0.1</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
Expand All @@ -196,34 +197,34 @@



<!-- https://github.com/ssscassio/ros-wall-follower-2-wheeled-robot/blob/master/report/Wall-following-algorithm-for-reactive%20autonomous-mobile-robot-with-laser-scanner-sensor.pdf
<!-- https://github.com/ssscassio/ros-wall-follower-2-wheeled-robot/blob/master/report/Wall-following-algorithm-for-reactive%20autonomous-mobile-robot-with-laser-scanner-sensor.pdf
Adding a laser scan sensor to the robot
-->
<link name="sensor_laser">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.4" />
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.02"/>
<mass value="0" />
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.02"/>
</inertial>

<visual>
<origin xyz="0.02 0 0" rpy="0 0 0" />
<origin xyz="${Factor*0.02} 0 0" rpy="0 0 0" />
<geometry>
<cylinder radius="0.005" length="0.022"/>
<cylinder radius="${Factor*0.005}" length="${Factor*0.022}"/>
</geometry>
<material name="white" />
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.005" length="0.022"/>
<cylinder radius="${Factor*0.005}" length="${Factor*0.022}"/>
</geometry>
</collision>
</link>

<joint name="joint_sensor_laser" type="fixed">
<origin rpy="0 0 -1.57" xyz="0 0 0.018"/>
<origin rpy="0 0 -1.57" xyz="0 0 ${Factor*0.018}"/>
<parent link="link_chassis"/>
<child link="sensor_laser"/>
</joint>
Expand Down Expand Up @@ -263,5 +264,5 @@
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>-->

</robot>
Loading

0 comments on commit c2379f4

Please sign in to comment.