diff --git a/rusty/launch/amcl.launch b/rusty/launch/amcl.launch
index 5ee9b66..32c2abd 100644
--- a/rusty/launch/amcl.launch
+++ b/rusty/launch/amcl.launch
@@ -1,27 +1,51 @@
+
+
+
+
+
-
-
-
-
-
+
+
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/rusty/launch/move_base.launch b/rusty/launch/move_base.launch
index ee18424..e0c7448 100644
--- a/rusty/launch/move_base.launch
+++ b/rusty/launch/move_base.launch
@@ -7,17 +7,27 @@
-
+
+
+
+
+
+
+
+
+
+
+
-
+
diff --git a/rusty/launch/navigation.launch b/rusty/launch/navigation.launch
index dd8d8f0..3c99e82 100644
--- a/rusty/launch/navigation.launch
+++ b/rusty/launch/navigation.launch
@@ -7,19 +7,20 @@
-
+
-
+
+
-
+
@@ -29,4 +30,9 @@
+
+
+
+
+ -->
diff --git a/rusty/launch/odomtransform.launch b/rusty/launch/odomtransform.launch
new file mode 100644
index 0000000..886eb02
--- /dev/null
+++ b/rusty/launch/odomtransform.launch
@@ -0,0 +1,8 @@
+
+
+
+
+
+
+
+
diff --git a/rusty/launch/robot_localize.launch b/rusty/launch/robot_localize.launch
new file mode 100644
index 0000000..37cdee8
--- /dev/null
+++ b/rusty/launch/robot_localize.launch
@@ -0,0 +1,55 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/rusty/launch/rusty_slam.launch b/rusty/launch/rusty_slam.launch
new file mode 100644
index 0000000..b8407a7
--- /dev/null
+++ b/rusty/launch/rusty_slam.launch
@@ -0,0 +1,71 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -->
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/rusty/robot_param/base_local_planner.yaml b/rusty/robot_param/base_local_planner.yaml
new file mode 100644
index 0000000..60405e3
--- /dev/null
+++ b/rusty/robot_param/base_local_planner.yaml
@@ -0,0 +1,23 @@
+controller_frequency: 10
+
+TrajectoryPlannerROS:
+ max_vel_x: 1.0
+ min_vel_x: -0.1
+ max_vel_theta: 1.57
+
+ min_in_place_vel_theta: 0.314
+
+ acc_lim_theta: 3.14
+ acc_lim_x: 2.0
+ acc_lim_y: 2.0
+
+ sim_time: 1.0
+
+ vx_samples: 5.0
+ vtheta_samples: 10.0
+
+ pdist_scale: 0.6 #0.6
+ gdist_scale: 0.8 #0.8
+ occdist_scale: 0.02
+
+ holonomic_robot: false
\ No newline at end of file
diff --git a/rusty/robot_param/costmap_common_params.yaml b/rusty/robot_param/costmap_common_params.yaml
new file mode 100644
index 0000000..f3ebc40
--- /dev/null
+++ b/rusty/robot_param/costmap_common_params.yaml
@@ -0,0 +1,12 @@
+obstacle_range: 4.0
+raytrace_range: 3.5
+
+#footprint: [[0.250, 0.300], [-0.250, 0.300], [-0.250, -0.300], [0.250, -0.300]]
+robot_radius: 0.305
+
+inflation_radius: 0.6
+cost_scaling_factor: 3.0
+
+map_type: costmap
+observation_sources: scan
+scan: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
diff --git a/rusty/robot_param/dwa_local_planner_params.yaml b/rusty/robot_param/dwa_local_planner_params.yaml
new file mode 100644
index 0000000..4a6cbd8
--- /dev/null
+++ b/rusty/robot_param/dwa_local_planner_params.yaml
@@ -0,0 +1,47 @@
+DWAPlannerROS:
+
+# Robot Configuration Parameters
+ max_vel_x: 0.35
+ min_vel_x: -0.20
+
+ max_vel_y: 0.0
+ min_vel_y: 0.0
+
+# The velocity when robot is moving in a straight line
+ max_vel_trans: 0.35
+ min_vel_trans: -0.25
+
+ max_vel_theta: 2.8
+ min_vel_theta: 1.5
+
+ acc_lim_x: 2.5
+ acc_lim_y: 0.0
+ acc_lim_theta: 3.2
+
+# Goal Tolerance Parametes
+ xy_goal_tolerance: 0.05
+ yaw_goal_tolerance: 0.17
+ latch_xy_goal_tolerance: false
+
+# Forward Simulation Parameters
+ sim_time: 1.4
+ vx_samples: 20
+ vy_samples: 0
+ vth_samples: 40
+ controller_frequency: 10.0
+
+# Trajectory Scoring Parameters
+ path_distance_bias: 25.0
+ goal_distance_bias: 10.0
+ occdist_scale: 0.02
+ forward_point_distance: 0.325
+ stop_time_buffer: 0.2
+ scaling_speed: 0.25
+ max_scaling_factor: 0.2
+
+# Oscillation Prevention Parameters
+ oscillation_reset_dist: 0.05
+
+# Debugging
+ publish_traj_pc : true
+ publish_cost_grid_pc: true
diff --git a/rusty/robot_param/global_costmap_params.yaml b/rusty/robot_param/global_costmap_params.yaml
new file mode 100644
index 0000000..c6bafdf
--- /dev/null
+++ b/rusty/robot_param/global_costmap_params.yaml
@@ -0,0 +1,10 @@
+global_costmap:
+ global_frame: map
+ robot_base_frame: base_link
+
+ update_frequency: 10.0
+ publish_frequency: 10.0
+ transform_tolerance: 0.5
+
+ static_map: true
+
diff --git a/rusty/robot_param/local_costmap_params.yaml b/rusty/robot_param/local_costmap_params.yaml
new file mode 100644
index 0000000..9b6e8d4
--- /dev/null
+++ b/rusty/robot_param/local_costmap_params.yaml
@@ -0,0 +1,14 @@
+local_costmap:
+ global_frame: odom
+ robot_base_frame: base_link
+
+ update_frequency: 10.0
+ publish_frequency: 10.0
+ transform_tolerance: 0.5
+
+ static_map: false
+ rolling_window: true
+ width: 4
+ height: 4
+ resolution: 0.05
+
diff --git a/rusty/robot_param/move_base_params.yaml b/rusty/robot_param/move_base_params.yaml
new file mode 100644
index 0000000..d4d706a
--- /dev/null
+++ b/rusty/robot_param/move_base_params.yaml
@@ -0,0 +1,9 @@
+shutdown_costmaps: false
+controller_frequency: 10.0
+planner_patience: 5.0
+controller_patience: 15.0
+conservative_reset_dist: 3.0
+planner_frequency: 10.0
+oscillation_timeout: 10.0
+oscillation_distance: 0.2
+
diff --git a/rusty_firmware/CMakeLists.txt b/rusty_firmware/CMakeLists.txt
new file mode 100644
index 0000000..364b04d
--- /dev/null
+++ b/rusty_firmware/CMakeLists.txt
@@ -0,0 +1,207 @@
+cmake_minimum_required(VERSION 3.0.2)
+project(rusty_firmware)
+
+## Compile as C++11, supported in ROS Kinetic and newer
+# add_compile_options(-std=c++11)
+
+## Find catkin macros and libraries
+## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
+## is used, also find other catkin packages
+find_package(catkin REQUIRED COMPONENTS
+ message_generation
+ roscpp
+ rospy
+ std_msgs
+)
+
+## System dependencies are found with CMake's conventions
+# find_package(Boost REQUIRED COMPONENTS system)
+
+
+## Uncomment this if the package has a setup.py. This macro ensures
+## modules and global scripts declared therein get installed
+## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
+# catkin_python_setup()
+
+################################################
+## Declare ROS messages, services and actions ##
+################################################
+
+## To declare and build messages, services or actions from within this
+## package, follow these steps:
+## * Let MSG_DEP_SET be the set of packages whose message types you use in
+## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
+## * In the file package.xml:
+## * add a build_depend tag for "message_generation"
+## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
+## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
+## but can be declared for certainty nonetheless:
+## * add a exec_depend tag for "message_runtime"
+## * In this file (CMakeLists.txt):
+## * add "message_generation" and every package in MSG_DEP_SET to
+## find_package(catkin REQUIRED COMPONENTS ...)
+## * add "message_runtime" and every package in MSG_DEP_SET to
+## catkin_package(CATKIN_DEPENDS ...)
+## * uncomment the add_*_files sections below as needed
+## and list every .msg/.srv/.action file to be processed
+## * uncomment the generate_messages entry below
+## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
+
+## Generate messages in the 'msg' folder
+# add_message_files(
+# FILES
+# Message1.msg
+# Message2.msg
+# )
+
+## Generate services in the 'srv' folder
+# add_service_files(
+# FILES
+# Service1.srv
+# Service2.srv
+# )
+
+## Generate actions in the 'action' folder
+# add_action_files(
+# FILES
+# Action1.action
+# Action2.action
+# )
+
+## Generate added messages and services with any dependencies listed here
+# generate_messages(
+# DEPENDENCIES
+# std_msgs
+# )
+
+################################################
+## Declare ROS dynamic reconfigure parameters ##
+################################################
+
+## To declare and build dynamic reconfigure parameters within this
+## package, follow these steps:
+## * In the file package.xml:
+## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
+## * In this file (CMakeLists.txt):
+## * add "dynamic_reconfigure" to
+## find_package(catkin REQUIRED COMPONENTS ...)
+## * uncomment the "generate_dynamic_reconfigure_options" section below
+## and list every .cfg file to be processed
+
+## Generate dynamic reconfigure parameters in the 'cfg' folder
+# generate_dynamic_reconfigure_options(
+# cfg/DynReconf1.cfg
+# cfg/DynReconf2.cfg
+# )
+
+###################################
+## catkin specific configuration ##
+###################################
+## The catkin_package macro generates cmake config files for your package
+## Declare things to be passed to dependent projects
+## INCLUDE_DIRS: uncomment this if your package contains header files
+## LIBRARIES: libraries you create in this project that dependent projects also need
+## CATKIN_DEPENDS: catkin_packages dependent projects also need
+## DEPENDS: system dependencies of this project that dependent projects also need
+catkin_package(
+# INCLUDE_DIRS include
+# LIBRARIES rusty_firmware
+# CATKIN_DEPENDS message_generation roscpp rospy std_msgs
+# DEPENDS system_lib
+)
+
+###########
+## Build ##
+###########
+
+## Specify additional locations of header files
+## Your package locations should be listed before other locations
+include_directories(
+# include
+ ${catkin_INCLUDE_DIRS}
+)
+
+## Declare a C++ library
+# add_library(${PROJECT_NAME}
+# src/${PROJECT_NAME}/rusty_firmware.cpp
+# )
+
+## Add cmake target dependencies of the library
+## as an example, code may need to be generated before libraries
+## either from message generation or dynamic reconfigure
+# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Declare a C++ executable
+## With catkin_make all packages are built within a single CMake context
+## The recommended prefix ensures that target names across packages don't collide
+# add_executable(${PROJECT_NAME}_node src/rusty_firmware_node.cpp)
+
+## Rename C++ executable without prefix
+## The above recommended prefix causes long target names, the following renames the
+## target back to the shorter version for ease of user use
+## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
+# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
+
+## Add cmake target dependencies of the executable
+## same as for the library above
+# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Specify libraries to link a library or executable target against
+# target_link_libraries(${PROJECT_NAME}_node
+# ${catkin_LIBRARIES}
+# )
+
+#############
+## Install ##
+#############
+
+# all install targets should use catkin DESTINATION variables
+# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
+
+## Mark executable scripts (Python etc.) for installation
+## in contrast to setup.py, you can choose the destination
+# catkin_install_python(PROGRAMS
+# scripts/my_python_script
+# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark executables for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
+# install(TARGETS ${PROJECT_NAME}_node
+# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark libraries for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
+# install(TARGETS ${PROJECT_NAME}
+# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
+# )
+
+## Mark cpp header files for installation
+# install(DIRECTORY include/${PROJECT_NAME}/
+# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+# FILES_MATCHING PATTERN "*.h"
+# PATTERN ".svn" EXCLUDE
+# )
+
+## Mark other files for installation (e.g. launch and bag files, etc.)
+# install(FILES
+# # myfile1
+# # myfile2
+# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+# )
+
+#############
+## Testing ##
+#############
+
+## Add gtest based cpp test target and link libraries
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_rusty_firmware.cpp)
+# if(TARGET ${PROJECT_NAME}-test)
+# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
+# endif()
+
+## Add folders to be run by python nosetests
+# catkin_add_nosetests(test)
diff --git a/rusty_firmware/launch/imu.launch b/rusty_firmware/launch/imu.launch
new file mode 100644
index 0000000..ccaa309
--- /dev/null
+++ b/rusty_firmware/launch/imu.launch
@@ -0,0 +1,10 @@
+
+
+
+
+
+
+
+
+
+
diff --git a/rusty_firmware/launch/lidar.launch b/rusty_firmware/launch/lidar.launch
new file mode 100644
index 0000000..f203b27
--- /dev/null
+++ b/rusty_firmware/launch/lidar.launch
@@ -0,0 +1,11 @@
+
+
+
+
+
+
+
+
+
+
+
diff --git a/rusty_firmware/launch/motor_run.launch b/rusty_firmware/launch/motor_run.launch
new file mode 100644
index 0000000..965b972
--- /dev/null
+++ b/rusty_firmware/launch/motor_run.launch
@@ -0,0 +1,13 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/rusty_firmware/package.xml b/rusty_firmware/package.xml
new file mode 100644
index 0000000..4418793
--- /dev/null
+++ b/rusty_firmware/package.xml
@@ -0,0 +1,69 @@
+
+
+ rusty_firmware
+ 0.0.0
+ The rusty_firmware package
+
+
+
+
+ pi
+
+
+
+
+
+ TODO
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ catkin
+ message_generation
+ roscpp
+ rospy
+ std_msgs
+ roscpp
+ rospy
+ std_msgs
+ roscpp
+ rospy
+ std_msgs
+
+
+
+
+
+
+
+
diff --git a/rusty_firmware/src/motor.py b/rusty_firmware/src/motor.py
new file mode 100644
index 0000000..a4b0a62
--- /dev/null
+++ b/rusty_firmware/src/motor.py
@@ -0,0 +1,137 @@
+#!/usr/bin/env python
+import rospy
+from geometry_msgs.msg import Twist
+import RPi.GPIO as GPIO
+import time
+from math import pi
+
+leftEn = 13 # Purple
+rightEn = 12 # Red
+
+leftBackward = 5 # Blue
+leftForward = 6 # Green
+rightForward = 16 # Yellow
+rightBackward = 20 # Orange
+
+wheel_separation = 0.40
+wheel_diameter = 0.065
+wheel_radius = wheel_diameter/2
+circumference_of_wheel = 2 * pi * wheel_radius
+
+GPIO.setmode(GPIO.BCM)
+GPIO.setwarnings(False)
+
+GPIO.setup(leftEn, GPIO.OUT)
+GPIO.setup(rightEn, GPIO.OUT)
+GPIO.setup(leftForward, GPIO.OUT)
+GPIO.setup(leftBackward, GPIO.OUT)
+GPIO.setup(rightForward, GPIO.OUT)
+GPIO.setup(rightBackward, GPIO.OUT)
+
+pwmL = GPIO.PWM(leftEn, 100)
+pwmL.start(0)
+pwmR = GPIO.PWM(rightEn, 100)
+pwmR.start(0)
+
+def stop():
+ #print('stopping')
+ pwmL.ChangeDutyCycle(0)
+ GPIO.output(leftForward, GPIO.HIGH)
+ GPIO.output(leftBackward, GPIO.HIGH)
+ pwmR.ChangeDutyCycle(0)
+ GPIO.output(rightForward, GPIO.HIGH)
+ GPIO.output(rightBackward, GPIO.HIGH)
+
+def forward(left_speed, right_speed):
+ #print('going forward')
+ lspeed = min(((left_speed/0.2)*100),100)
+ rspeed = min(((right_speed/0.2)*100),100)
+ #print(str(left_speed)+" "+str(right_speed))
+ pwmL.ChangeDutyCycle(lspeed)
+ pwmR.ChangeDutyCycle(rspeed)
+ GPIO.output(leftForward, GPIO.HIGH)
+ GPIO.output(rightForward, GPIO.HIGH)
+ GPIO.output(leftBackward, GPIO.LOW)
+ GPIO.output(rightBackward, GPIO.LOW)
+
+def backward(left_speed, right_speed):
+ #print('going backward')
+ lspeed = min(((left_speed/0.2)*100),100)
+ rspeed = min(((right_speed/0.2)*100),100)
+ #print(str(left_speed)+" "+str(right_speed))
+ pwmL.ChangeDutyCycle(lspeed)
+ pwmR.ChangeDutyCycle(rspeed)
+ GPIO.output(leftForward, GPIO.LOW)
+ GPIO.output(rightForward, GPIO.LOW)
+ GPIO.output(leftBackward, GPIO.HIGH)
+ GPIO.output(rightBackward, GPIO.HIGH)
+
+def left(left_speed, right_speed):
+ #print('turning left')
+ lspeed = min(((left_speed/0.2)*100),100)
+ rspeed = min(((right_speed/0.2)*100),100)
+ pwmL.ChangeDutyCycle(lspeed)
+ pwmR.ChangeDutyCycle(rspeed)
+ GPIO.output(leftForward, GPIO.LOW)
+ GPIO.output(leftBackward, GPIO.HIGH)
+ GPIO.output(rightForward, GPIO.HIGH)
+ GPIO.output(rightBackward, GPIO.LOW)
+
+def right(left_speed, right_speed):
+ #print('turning right')
+ lspeed = min(((left_speed/0.2)*100),100)
+ rspeed = min(((right_speed/0.2)*100),100)
+ pwmL.ChangeDutyCycle(lspeed)
+ pwmR.ChangeDutyCycle(rspeed)
+ GPIO.output(leftForward, GPIO.HIGH)
+ GPIO.output(leftBackward, GPIO.LOW)
+ GPIO.output(rightForward, GPIO.LOW)
+ GPIO.output(rightBackward, GPIO.HIGH)
+
+def callback(data):
+
+ global wheel_radius
+ global wheel_separation
+
+ linear_vel = data.linear.x
+ angular_vel = data.angular.z
+ #print(str(linear)+"\t"+str(angular))
+
+ rplusl = ( 2 * linear_vel ) / wheel_radius
+ rminusl = ( angular_vel * wheel_separation ) / wheel_radius
+
+ right_omega = ( rplusl + rminusl ) / 2
+ left_omega = rplusl - right_omega
+
+ right_vel = right_omega * wheel_radius
+ left_vel = left_omega * wheel_radius
+
+ #print (str(left_vel)+"\t"+str(right_vel))
+ '''
+ left_speed = abs ( linear - ( (wheel_separation/2) * (angular) ) )
+ right_speed = abs ( linear - ( (wheel_separation/2) * (angular) ) )
+ '''
+
+ if (left_vel == 0.0 and right_vel == 0.0):
+ stop()
+ elif (left_vel >= 0.0 and right_vel >= 0.0):
+ forward(abs(left_vel), abs(right_vel))
+ elif (left_vel <= 0.0 and right_vel <= 0.0):
+ backward(abs(left_vel), abs(right_vel))
+ elif (left_vel < 0.0 and right_vel > 0.0):
+ left(abs(left_vel), abs(right_vel))
+ elif (left_vel > 0.0 and right_vel < 0.0):
+ right(abs(left_vel), abs(right_vel))
+ else:
+ stop()
+
+
+
+def listener():
+ rospy.init_node('motorcontrol', anonymous=False)
+ rospy.Subscriber("/cmd_vel", Twist, callback)
+ rospy.spin()
+
+if __name__== '__main__':
+ print('ARJUN INITIALIZED')
+ listener()