Skip to content

Commit

Permalink
removed RGB,Binary,GS values publisher
Browse files Browse the repository at this point in the history
- pixel_values publisher takes care of those 3 scripts
The scripts are now moved to the 'trash' folder
  • Loading branch information
MohammadKhan-3 committed Apr 18, 2022
1 parent c2aa0d3 commit 9dfdb25
Show file tree
Hide file tree
Showing 14 changed files with 265 additions and 124 deletions.
6 changes: 5 additions & 1 deletion msg/BinaryState.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,8 @@
# (0) turns off the LED
#

uint8 binary # single channel
# uint8 binary # single channel

uint8 red # red channel
uint8 green # green channel
uint8 blue # blue channel
165 changes: 165 additions & 0 deletions scripts/No_Descartes_Robot_Motion.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
#!/usr/bin/env python3

import rospy
from robot_control import *
import copy
from geometry_msgs.msg import Pose


import time

# For Image Manipulation
import cv2
import numpy as np

# Custom Scripts
import image_inputs as input_image
from pixel_value_publisher import pixel_value_publisher

#Custom Message
from light_painting.msg import RGBState
"""
Script does not use Descartes. Solely ROS MoveIt planner
- Uses image Processing Class
- Need to clean up robot motion as well
"""


#------------------------ Global Variables -----------------
MOTION_BOX_scale = 0.01 # m
# import image
img = input_image.RGB

# Box length (m)
IMAGE_HEIGHT = np.size(img,0)
print('height of image',IMAGE_HEIGHT)
IMAGE_WIDTH = np.size(img,1)
print('Width of image',IMAGE_WIDTH)

row = range(IMAGE_HEIGHT) # [0,1,2]
col = range(IMAGE_WIDTH) # [0,1,2]

# real world box size
MOTION_BOX_WIDTH = IMAGE_WIDTH*MOTION_BOX_scale # m
MOTION_BOX_HEIGHT = IMAGE_HEIGHT*MOTION_BOX_scale # m



# Starting positions for robot
z_start = 1 # m
y_start = -MOTION_BOX_WIDTH/2 # m
#----------------------------------

def nextRow(wpose):
# Purpose: moves robot to next row
wpose.position.z -= MOTION_BOX_scale
wpose.position.y = y_start # same y-axis starting value
waypoints= []
waypoints.append(copy.deepcopy(wpose))
return waypoints

def nextColumn(wpose):
# Purpose: increments to next column
wpose.position.y += MOTION_BOX_scale
waypoints= []
waypoints.append(copy.deepcopy(wpose))
return waypoints

def main():

move_robot = True # set equal to False to not move robot

# Setup
pixel_value = pixel_value_publisher()

# init node & Publishers
pub_rgb_values = rospy.Publisher('/paintbrush',RGBState, queue_size=5)

This comment has been minimized.

Copy link
@acbuynak

acbuynak Apr 20, 2022

Member

@MohammadKhan-3
Incorrect topic name. Should be /paintbrush_color

Must match line in Arduino control script:

ros::Subscriber<light_painting::RGBState> sub_led_state("paintbrush_color", &paintColorCallback );

This comment has been minimized.

Copy link
@acbuynak

acbuynak Apr 20, 2022

Member

Resolved by fbca900

rospy.init_node('van gogh')
rospy.loginfo(">>van gogh node successfully created")
rospy.Rate(1)

# Initialize Robot Model
rc= moveManipulator('mh5l')
rc.set_vel(0.1)
rc.set_accel(0.1)

# If Move_robot = True, then robot will always start at all-zeros
if move_robot:
rc.goto_all_zeros()

# Based on global variables, robot goes to arbitrary start position
# Top Left is origin (similar to image origin in computer graphics)
waypoints = []
start_pose = rc.move_group.get_current_pose().pose
start_pose.position.z = z_start
start_pose.position.y = y_start

if move_robot:
rc.goto_Pose(start_pose)

# Creating nested for loop to iteratre through all pixels
for i in row:

if i != 0: # As long as i is not 0, then move to the next row.
# i = 0, is the first row --> no need to move to next row
# i = 1,2 are the next two rows
print('reset to next row')
print("Pixel on row {}" .format(i))
wpose = rc.move_group.get_current_pose().pose
pixel_value.RGB_img(pub_rgb_values)
#sendRGB2LED(pub_rgb_values)
waypoints = nextRow(wpose)

if move_robot:
plan, fraction = rc.plan_cartesian_path(waypoints)
rc.execute_plan(plan)


for j in col:
print("Pixel on row {} and col {}" .format(i,j))
r,g,b = img[i,j].astype('uint8')
# v = img[i,j].astype('uint8')


if j != 0:
# if not initial column, keep moving horizontally
print('Keep moving horizontally')
print("Pixel on row {} and col {}" .format(i,j))
wpose = rc.move_group.get_current_pose().pose
waypoints = nextColumn(wpose)

# input(f"Cartesian Plan {i}: press <enter>") # uncomment this line if you want robot to run automatically
if move_robot:
plan, fraction = rc.plan_cartesian_path(waypoints)
rc.execute_plan(plan)
# sendRGB2LED(pub_rgb_values,r,g,b) # sends publisher handle & r,g,b values to RGB Led Via ROS

delay =0.5
print('Delay (sec):',delay)

pixel_value.RGB_img(pub_rgb_values,r,g,b)
time.sleep(delay) # Delay keeps light on/off for certain amount of time for consistent lumosity

pixel_value.RGB_img(pub_rgb_values)
# by default r,g,b=0 in sendRGB2LED() function, sending just pub handle, turns off RGB
time.sleep(0.05)
if move_robot:
pixel_value.RGB_img(pub_rgb_values)
rc.goto_all_zeros()


try:
rospy.spin()
except KeyboardInterrupt:
print("Shutting down")
cv2.destroyAllWindows()


if __name__ == '__main__':
try:
main()

except rospy.ROSInterruptException:
print("program interrupted before completion", file=sys.stderr)


9 changes: 5 additions & 4 deletions scripts/RGB_no_descartes_robot_motion.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,6 @@
#Custom Message
from light_painting.msg import RGBState

# -----------------------------
# Script uses ROS Publisher to communicate with Arduino.
# Script uses ROS built in MoveIt Cartesian Motion planner. NOT DESCARTES

#------------------------ Global Variables -----------------
MOTION_BOX_scale = 0.01 # m
Expand Down Expand Up @@ -111,7 +108,6 @@ def main():

for j in col:
print("Pixel on row {} and col {}" .format(i,j))

r,g,b = img[i,j].astype('uint8')
# v = img[i,j].astype('uint8')

Expand All @@ -131,11 +127,16 @@ def main():

delay =0.5
print('Delay (sec):',delay)

sendRGB2LED(pub_rgb_values,r,g,b) # sends publisher handle & r,g,b values to RGB Led Via ROS
time.sleep(delay) # Delay keeps light on/off for certain amount of time for consistent lumosity

sendRGB2LED(pub_rgb_values)
# by default r,g,b=0 in sendRGB2LED() function, sending just pub handle, turns off RGB
time.sleep(0.05)
if move_robot:
sendRGB2LED(pub_rgb_values)
rc.goto_all_zeros()
try:
rospy.spin()
except KeyboardInterrupt:
Expand Down
68 changes: 15 additions & 53 deletions scripts/binary_no_descartes_robot_motion.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,26 +5,21 @@
import copy
from geometry_msgs.msg import Pose

# # For Arduino Control
# import time
# import serial
# arduino = serial.Serial(port='/dev/ttyACM0',baudrate=9600,timeout=0.1)
import time

# For Image Manipulation
import cv2
import numpy as np

# Custom Scripts
# import py_to_ino_LIGHT_ON_OFF_test as arduino_led
import image_inputs as input_image
from Binary_values_publisher import sendBinary2LED
from RGB_values_publisher import sendRGB2LED

# ROS Data Types
from light_painting.msg import BinaryState
from light_painting.msg import RGBState


#--------- Description of Script
# Script uses Serial Connection to Arduino to
# send pixel values of Binary Image

#------------------------ Global Variables -----------------

Expand Down Expand Up @@ -76,7 +71,7 @@ def main():
move_robot = True

# Init Node
pub_binary_values = rospy.Publisher('/paintbrush_binary', BinaryState, queue_size=1)
pub_binary_values = rospy.Publisher('/paintbrush_binary', RGBState, queue_size=5)
rospy.init_node('Seurat')
rospy.loginfo(">>seurat paint node successfully created")
rospy.Rate(1)
Expand Down Expand Up @@ -105,6 +100,7 @@ def main():
print('reset to next row')
print("Pixel on row {}" .format(i))
wpose = rc.move_group.get_current_pose().pose
sendRGB2LED(pub_binary_values)
waypoints = nextRow(wpose)

if move_robot:
Expand All @@ -126,11 +122,14 @@ def main():
if move_robot:
plan, fraction = rc.plan_cartesian_path(waypoints)
rc.execute_plan(plan)
sendBinary2LED(pub_binary_values,v) # sends publisher handle & binar values to Led Via ROS
# time.sleep(0.5) # delay alters lumosity of light
sendBinary2LED(pub_binary_values) # by default: v = 0 in sendBinary2LED function (LED is off)
# time.sleep(0.5)
#
sendRGB2LED(pub_binary_values,v,v,v) # sends publisher handle & binar values to Led Via ROS
time.sleep(0.5) # delay alters lumosity of light
sendRGB2LED(pub_binary_values) # by default: v = 0 in sendBinary2LED function (LED is off)
time.sleep(0.5)
if move_robot:
sendRGB2LED(pub_binary_values)
rc.goto_all_zeros()


try:
rospy.spin()
Expand All @@ -142,41 +141,4 @@ def main():
try:
main()
except rospy.ROSInterruptException:
print("program interrupted before completion", file=sys.stderr)




# # Turn LED ON/OFF depending upon pixel value
# if img.item(i) == 0:
# arduino_led.led_OFF()
# time.sleep(0.5)
# # Delay keeps light on/off for certain amount of time for consistent lumosity
# else:
# arduino_led.led_ON()
# arduino_led.led_OFF() # Turns off after every movement - remove this for continuous LED ON
# time.sleep(0.5)

# if i == 0:
# waypoints = []
# print('i=',i)
# print('wpose.position.y=',wpose.position.y)
# elif i % IMAGE_WIDTH == 0: # if i is a multiple of the image width, that means it should move to the next row
# print('Reached end of row, starting next row at index: ',i)
# wpose.position.z -= MOTION_BOX_HEIGHT/IMAGE_HEIGHT
# wpose.position.y = y_start # same y-axis starting value
# waypoints.append(copy.deepcopy(wpose))
# print('i=',i)
# print('wpose.position.y=',wpose.position.y)

# else: # else keep incrementally moving horizontally across y-axis
# wpose.position.y += MOTION_BOX_WIDTH/IMAGE_WIDTH # Previously, MOTION_BOX_LENGTH/WIDTH = 3/9=1/3 m big jump
# waypoints.append(copy.deepcopy(wpose))
# print('i=',i)
# print('wpose.position.y=',wpose.position.y)

# if move_robot:
# plan, fraction = rc.plan_cartesian_path(waypoints)
# rc.execute_plan(plan)

# rc.goto_all_zeros()
print("program interrupted before completion", file=sys.stderr)
3 changes: 1 addition & 2 deletions scripts/grayscale_no_descartes_robot_motion.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,7 @@ def main():

move_robot = True # set equal to False to not move robot

# init node & Publishers
# pub_GS_values = rospy.Publisher('/paintbrush_grayscale',GrayScale, queue_size=1)
# init node & Publishers
pub_GS_values = rospy.Publisher('/paintbrush_color',RGBState, queue_size=1)

rospy.init_node('grayscale')
Expand Down
6 changes: 3 additions & 3 deletions scripts/image_inputs.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
GRAYSCALE = join(RESOURCES,'grayscale')
R_G_B = join(RESOURCES,'RGB')

#Binary Images:
########### Binary Images:###################
white_rim4x3 = 'white_rim_4x3.tif'
white_rim3x3 = 'white_rim_3x3.tif'
blockO = 'block-O_10x10.tif'
Expand All @@ -22,7 +22,7 @@
# binary = cv2.imread(join(BINARY,blockO),0)
# binary = cv2.imread(join(BINARY,aims),0)

#RGB images:
################### RGB images: #####################
green_cross = 'green_cross.tif' # 3x3 image
blockO_rgb = 'block_o_RGB.tif' # 10x10 image

Expand All @@ -32,7 +32,7 @@
# BGR = cv2.imread(join(R_G_B,blockO_rgb))
# RGB = cv2.cvtColor(BGR,cv2.COLOR_BGR2RGB)

# GrayScale
################# GrayScale Images ##################
# sweep_10x20 = 'sweep.tif'
# sweep_3x3 = 'sweep_3x3.tif'
# sweep_3x5 = 'sweep_3x5.tif'
Expand Down
Loading

0 comments on commit 9dfdb25

Please sign in to comment.