-
pateman16 authored5416119a
action_controller.py 7.11 KiB
#!/usr/bin/env python
import roslib
roslib.load_manifest('simulation_control')
import rospy
import actionlib
import mavros_state
import time
from autonomous_offboard.msg import center_on_objectAction, center_on_objectGoal, descend_on_objectAction, descend_on_objectGoal, detect_objectAction, detect_objectGoal, goto_positionAction, goto_positionGoal, short_grippersAction, short_grippersGoal, long_grippersAction, long_grippersGoal, coverageAction, coverageGoal
from std_msgs.msg import Float32
from geometry_msgs.msg import PoseStamped
if __name__ == '__main__':
rospy.init_node('action_controller')
mv_state = mavros_state.mavros_state()
print 'Setting offboard'
mv_state.set_mode('OFFBOARD')
print 'Arming vehicle'
mv_state.arm(True)
rospy.loginfo("Taking off")
goto_position_client = actionlib.SimpleActionClient('goto_position', goto_positionAction)
goto_position_client.wait_for_server()
goto_position_goal = goto_positionGoal()
goto_position_goal.destination.pose.position.z = 5
goto_position_client.send_goal(goto_position_goal)
goto_position_client.wait_for_result()
rospy.loginfo("Takeoff succeded")
# Close legs
long_grippers_client = actionlib.SimpleActionClient('long_grippers', long_grippersAction)
long_grippers_client.wait_for_server()
rospy.loginfo("Moving legs to pickup position")
long_grippers_goal = long_grippersGoal(grip_rad_goal=Float32(0.5000000000))
long_grippers_client.send_goal(long_grippers_goal)
long_grippers_client.wait_for_result()
if long_grippers_client.get_result().goal_reached.data:
rospy.loginfo("Legs moved to pickup position")
else:
rospy.loginfo("Error with moving legs to pickup position")
# /Close legs
coverage_client = actionlib.SimpleActionClient('coverage', coverageAction)
coverage_client.wait_for_server()
coverage_goal = coverageGoal()
coverage_goal.destination.pose.position.x = -105
coverage_goal.destination.pose.position.y = 0
coverage_goal.destination.pose.position.z = 10
coverage_client.send_goal(coverage_goal)
coverage_client.wait_for_result()
res = PoseStamped()
res = coverage_client.get_result().detected_object_pos
rospy.loginfo("Detected object is at position (x,y,z)=({}, {}, {})".format(
res.pose.position.x,
res.pose.position.y,
res.pose.position.z))
rospy.loginfo("Going to detected position")
goto_position_goal.destination.pose.position.x = coverage_client.get_result().detected_object_pos.pose.position.x
goto_position_goal.destination.pose.position.y = coverage_client.get_result().detected_object_pos.pose.position.y
goto_position_goal.destination.pose.position.z = coverage_client.get_result().detected_object_pos.pose.position.z
goto_position_client.send_goal(goto_position_goal)
goto_position_client.wait_for_result()
rospy.loginfo("Is at position (x,y,z)=({}, {}, {})".format(coverage_client.get_result().detected_object_pos.pose.position.x,
coverage_client.get_result().detected_object_pos.pose.position.y,
coverage_client.get_result().detected_object_pos.pose.position.z))
rospy.loginfo("Descending on object")
descend_on_object_client = actionlib.SimpleActionClient('descend_on_object', descend_on_objectAction)
descend_on_object_client.wait_for_server()
rospy.loginfo("Descending server started")
descend_on_object_goal = descend_on_objectGoal()
descend_on_objectGoal = 2.0
descend_on_object_client.send_goal(descend_on_object_goal)
descend_on_object_client.wait_for_result()
if descend_on_object_client.get_result().position_reached.data:
print("landing")
mv_state.arm(False)
else:
rospy.loginfo("Couldnt land exiting")
time.sleep(3)
# Grip object
short_grippers_client = actionlib.SimpleActionClient('short_grippers', short_grippersAction)
short_grippers_client.wait_for_server()
rospy.loginfo("Closing short grippers")
short_grippers_goal = short_grippersGoal(grip_rad_goal=Float32(1.22000000000))
short_grippers_client.send_goal(short_grippers_goal)
short_grippers_client.wait_for_result()
if short_grippers_client.get_result().goal_reached.data:
rospy.loginfo("Short grippers closed")
else:
rospy.loginfo("Error when closing short grippers")
# /Grip object
time.sleep(3)
print 'Setting offboard'
mv_state.set_mode('OFFBOARD')
print 'Arming vehicle'
mv_state.arm(True)
time.sleep(1)
rospy.loginfo("Lifting")
goto_position_goal.destination.pose.position.x = -105
goto_position_goal.destination.pose.position.y = 0
goto_position_goal.destination.pose.position.z = 1.5
goto_position_client.send_goal(goto_position_goal)
goto_position_client.wait_for_result()
time.sleep(1)
# Close legs
rospy.loginfo("Closing legs around object")
long_grippers_goal = long_grippersGoal(grip_rad_goal=Float32(1.57000000000))
long_grippers_client.send_goal(long_grippers_goal)
long_grippers_client.wait_for_result()
if long_grippers_client.get_result().goal_reached.data:
print("Legs closed")
else:
rospy.loginfo("Error with closing legs")
# /Close legs
time.sleep(1)
rospy.loginfo("Going to drop off position")
goto_position_goal.destination.pose.position.x = 0
goto_position_goal.destination.pose.position.y = 105
goto_position_goal.destination.pose.position.z = 5
goto_position_client.send_goal(goto_position_goal)
goto_position_client.wait_for_result()
time.sleep(3)
rospy.loginfo("Deceding prior to drop off")
goto_position_goal.destination.pose.position.x = 0
goto_position_goal.destination.pose.position.y = 105
goto_position_goal.destination.pose.position.z = 0.5
goto_position_client.send_goal(goto_position_goal)
goto_position_client.wait_for_result()
time.sleep(3)
# Open legs
rospy.loginfo("Opening legs around object")
long_grippers_goal = long_grippersGoal(grip_rad_goal=Float32(0.00000000000))
long_grippers_client.send_goal(long_grippers_goal)
long_grippers_client.wait_for_result()
if long_grippers_client.get_result().goal_reached.data:
print("Legs opened")
else:
rospy.loginfo("Error with leg opening")
# /Open legs
time.sleep(1)
# Release object
rospy.loginfo("short_grippers")
short_grippers_goal = short_grippersGoal(grip_rad_goal=Float32(0.00000000000))
short_grippers_client.send_goal(short_grippers_goal)
short_grippers_client.wait_for_result()
if short_grippers_client.get_result().goal_reached.data:
print("Grip position reached")
else:
rospy.loginfo("Grip position not reached")
# /Release object
time.sleep(3)
rospy.loginfo("Going Home")
goto_position_goal.destination.pose.position.x = 0
goto_position_goal.destination.pose.position.y = -105
goto_position_goal.destination.pose.position.z = 5
goto_position_client.send_goal(goto_position_goal)
goto_position_client.wait_for_result()
mv_state.land(0.0)