Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Changes made: #39

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 30 additions & 0 deletions assignment_2/AlphaMale1996_pid_control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)

# Set the build type. Options are:
# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
# Debug : w/ debug symbols, w/o optimization
# Release : w/o debug symbols, w/ optimization
# RelWithDebInfo : w/ debug symbols, w/ optimization
# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
#set(ROS_BUILD_TYPE RelWithDebInfo)

rosbuild_init()

#set the default path for built executables to the "bin" directory
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
#set the default path for built libraries to the "lib" directory
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)

#uncomment if you have defined messages
#rosbuild_genmsg()
#uncomment if you have defined services
#rosbuild_gensrv()

#common commands for building c++ executables and libraries
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
#target_link_libraries(${PROJECT_NAME} another_library)
#rosbuild_add_boost_directories()
#rosbuild_link_boost(${PROJECT_NAME} thread)
#rosbuild_add_executable(example examples/example.cpp)
#target_link_libraries(example ${PROJECT_NAME})
1 change: 1 addition & 0 deletions assignment_2/AlphaMale1996_pid_control/Makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
include $(shell rospack find mk)/cmake.mk
91 changes: 91 additions & 0 deletions assignment_2/AlphaMale1996_pid_control/Planar.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
#!/usr/bin/env python

PKG = 'seabotix'

from pid import PID
import roslib; roslib.load_manifest(PKG)
import rospy
from kraken_msgs.msg import thrusterData6Thruster
from kraken_msgs.msg import thrusterData4Thruster
from kraken_msgs.msg import positionData
from resources import topicHeader
import numpy as np
from math import *
from std_msgs.msg import Float64
from geometry_msgs.msg import Pose
POS = PID()

#Defining global variables
Curr_x = 0.0
Goal_x = 0.0
Base_x = 0.0
prevError = 0.0
errorI = 0.0
errorP = 0.0
errorD = 0.0
out = 0.0
FIRST_ITERATION = True


def posCB(dataIn):
global Curr_x
global Base_x
global prevError
global errorD
global errorI
global errorP
global FIRST_ITERATION
global out

if FIRST_ITERATION:
Base_x = dataIn.position.x
FIRST_ITERATION = False

Curr_x = dataIn.position.x
print 'Position ',Curr_x,' : ',Base_x
prevError = errorP
print 'Error ',errorP
errorP = Goal_x - Curr_x
errorI = errorP + prevError
errorD = errorP - prevError
out = POS.k[0]*errorP + POS.k[1]*errorD + POS.k[2]*errorI

thruster6Data = thrusterData6Thruster()
thruster4Data = thrusterData4Thruster()

def runPLANAR():

global Goal_x


print 'Enter the goal position : '
Goal_x = float(raw_input())
rospy.init_node('Control', anonymous=True)
sub = rospy.Subscriber("/g500/pose", Pose, posCB)
pub4 = rospy.Publisher(topicHeader.CONTROL_PID_THRUSTER4, thrusterData4Thruster, queue_size = 2)
pub6 = rospy.Publisher(topicHeader.CONTROL_PID_THRUSTER6, thrusterData6Thruster, queue_size = 2)
puberror = rospy.Publisher('ErrorPose', Float64, queue_size = 2)
r = rospy.Rate(10)

while not rospy.is_shutdown():

thruster6Data.data[0] = 0.0
thruster6Data.data[1] = 0.0
thruster6Data.data[2] = 0.0
thruster6Data.data[3] = 0.0

thruster6Data.data[4] = out
thruster6Data.data[5] = out

thruster4Data.data[0] = thruster6Data.data[0]
thruster4Data.data[1] = thruster6Data.data[1]
thruster4Data.data[2] = thruster6Data.data[4]
thruster4Data.data[3] = thruster6Data.data[5]

pub4.publish(thruster4Data)
pub6.publish(thruster6Data)
puberror.publish(errorP)

r.sleep()


Empty file.
Loading