Skip to content

Commit

Permalink
Uploaded Files
Browse files Browse the repository at this point in the history
  • Loading branch information
aryadas98 authored Nov 21, 2019
1 parent 609b53f commit 5f46f27
Show file tree
Hide file tree
Showing 8 changed files with 447 additions and 2 deletions.
Binary file added Alligator Inspired Robot Report.pdf
Binary file not shown.
205 changes: 205 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,205 @@
cmake_minimum_required(VERSION 2.8.3)
project(bio-robotics-project)

## 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
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 bio-robotics-project
# CATKIN_DEPENDS 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}/bio-robotics-project.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/bio-robotics-project_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
# install(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_bio-robotics-project.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)
17 changes: 15 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,2 +1,15 @@
# bio-inspired-robotics
Bio Inspired Robotics Project ME335 Project
# Alligator Inspired Robot
Bio Inspired Robotics (ME335) Project under Dr. Atul Thakur

This is a simulation based project. The objective is to make a simulated alligator inspired robot go through a set of waypoints. The simulation is done in V-REP and we use ROS and OpenCV to do image processing. Low level commands used for trotting are handled by a Lua script in V-REP.

Check out the [report](Alligator%20Inspired%20Robot%20Report.pdf) to know more.

## Instructions to run the project:
Install V-REP and ROS and make sure that the `vrep-ros-interface` is working. Put the `alligator.lua` file in the V-REP path such that it is accessible in V-REP. The folder `bio-inspired-robotics` is a ROS package. Put it in the correct place and make sure `catkin_make` runs successfully. Now load `alligator.ttt` in V-REP and start the simulation. Start ROS and in a terminal type `rosrun bio-inspired-robotics alligator-controller.py`.

![](screenshot.png)

Contributers:
Arya Das
Shubham Chouksey
Binary file added bio-inspired-robotics/src/Alligator.ttt
Binary file not shown.
54 changes: 54 additions & 0 deletions bio-inspired-robotics/src/alligator-controller.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
#!/usr/bin/env python

import rospy
from std_msgs.msg import Int8
from sensor_msgs.msg import Image
import cv2
import numpy as np
from cv_bridge import CvBridge,CvBridgeError

bridge = CvBridge()

stop, straight, right, left = 0,1,2,3
dirr = stop

def callback(msg):
img = bridge.imgmsg_to_cv2(msg)
img = cv2.flip(img,0)
imgf = cv2.inRange(img, (0,100,0), (50,255,50))

count = cv2.countNonZero(imgf)
cX, cY, dirr = -1,-1,stop

if (count > 0):
M = cv2.moments(imgf)

cX = int(M["m10"] / M["m00"])
cY = int(M["m01"] / M["m00"])

if (count == 0):
dirr = stop
elif (cX < 11):
dirr = left
elif (cX > 21):
dirr = right
else:
dirr = straight

print("px count:", count, "centroid:",cX,cY, "direction:",dirr)
pub.publish(dirr)

newimgf = np.ones_like(img)*255
newimgf = cv2.bitwise_or(newimgf,newimgf,mask=imgf)

disp = np.concatenate((img,newimgf), axis=1)
disp = cv2.resize(disp,(0,0),fx=10,fy=10,interpolation=cv2.INTER_NEAREST)

cv2.imshow("Display", disp)
cv2.waitKey(1)

rospy.init_node('controller', anonymous=True)
rospy.Subscriber('image', Image, callback)
pub = rospy.Publisher('alg_ctrl', Int8, queue_size=10)

rospy.spin()
99 changes: 99 additions & 0 deletions bio-inspired-robotics/src/alligator.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
jointNames = {
'ThighJoint_Front_Right',
'KneeJoint_Front_Right',
'LowerLeg_Front_Right',

'ThighJoint_Front_Right0',
'KneeJoint_Front_Right0',
'LowerLeg_Front_Right0',

'ThighJoint_Front_Right1',
'KneeJoint_Front_Right1',
'LowerLeg_Front_Right1',

'ThighJoint_Front_Right2',
'KneeJoint_Front_Right2',
'LowerLeg_Front_Right2'
}

trotParams = {
{0, 0.3, 0},
{0, 0.0, 1.5},
{0, 0, 0},

{0, 0.3, 1},
{0, 0.3, 0.5},
{0, 0, 0},

{0, 0.3, 1},
{0, 0.3, 1.5},
{0, 0, 0},

{0, 0.3, 0},
{0, 0.0, 0.5},
{0, 0, 0}
}

omega = 2*math.pi

stop, straight, right, left = 0, 1, 2, 3

state = stop

function sysCall_init()
handles = {}
for i = 1,12 do
handles[i] = sim.getObjectHandle(jointNames[i])
end

baseVisionSensor = sim.getObjectHandle('base_vision_sensor')

pub=simROS.advertise('/image', 'sensor_msgs/Image')
simROS.publisherTreatUInt8ArrayAsString(pub)

sub=simROS.subscribe('/alg_ctrl', 'std_msgs/Int8', 'alg_ctrl_callback')
end

function sysCall_actuation()
if state == stop then
for i=1,12 do sim.setJointTargetPosition(handles[i],0) end
return
elseif state == straight then
trotParams[1][2] = 0.3
trotParams[4][2] = 0.3
trotParams[7][2] = 0.3
trotParams[10][2] = 0.3
elseif state == right then
trotParams[1][2] = 0.0
trotParams[4][2] = 0.0
trotParams[7][2] = 0.3
trotParams[10][2] = 0.3
elseif state == left then
trotParams[1][2] = 0.3
trotParams[4][2] = 0.3
trotParams[7][2] = 0.0
trotParams[10][2] = 0.0
end

for i=1,12 do
angle = trotParams[i][1] + trotParams[i][2]*math.sin(omega*sim.getSimulationTime() + trotParams[i][3]*math.pi)
sim.setJointTargetPosition(handles[i],angle)
end
end

function sysCall_sensing()
local data,w,h=sim.getVisionSensorCharImage(baseVisionSensor)
d={}
d['header']={seq=0,stamp=simROS.getTime(), frame_id="a"}
d['height']=h
d['width']=w
d['encoding']='rgb8'
d['is_bigendian']=1
d['step']=w*3
d['data']=data
simROS.publish(pub,d)
end

function alg_ctrl_callback(msg)
state = msg.data
end
Loading

0 comments on commit 5f46f27

Please sign in to comment.