Commit 3511de2a authored by master's avatar master

init

parents
cmake_minimum_required(VERSION 2.8.3)
project(robot_motion)
## 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
)
## 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 # Or other packages containing 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 odom2pose
# CATKIN_DEPENDS rospy
# 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}/odom2pose.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/odom2pose_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/robot_motion
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_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
scripts/robot_motion
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_odom2pose.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)
<?xml version="1.0"?>
<package format="2">
<name>robot_motion</name>
<version>0.0.0</version>
<description>The robot_motion package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="elwan.hery@hds.utc.fr">Elwan HERY</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/odom2pose</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>rospy</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
Node : robot_motion
Permet au robot d'avancer ou de reculer d'une distance donnée ou de tourner d'un angle donné.
Entrées :
Topic par default : /pose_odom (à modifier si besoin)
Type de message : PoseStamped
Permet d'obtenir la pose du robot utilisée pour la régulation.
Topic par default : /move_forward
Type de message : Float32
Consigne de distance (à envoyer une seule fois),
le robot avancera si la consigne est positive et reculera sinon.
Topic par default : /turn_left
Type de message : Float32
Consigne d'angle (à envoyer une seule fois),
le robot tournera à droite si la consigne est positive et à gauche sinon.
Sorties :
Topic par default : /cmd_vel
Type de message : Twist
Consigne de vitesse envoyée aux servomoteurs du robot.
Topic par default : /move_forward_finished
Type de message : Bool
Booléen passant à False lorsque la consigne de distance est reçu et
à True lorsque le roboot est arrivé à destination.
Topic par default : /move_forward_finished
Type de message : Bool
Booléen passant à False lorsque la consigne d'angle est reçu et
à True lorsque le roboot est arrivé à destination.
Paramètres :
self.K_p = np.array([1, 1])
Coefficients du régulateur proportionnel en distance et en angle.
self.max_speed = np.array([0.05, 0.5])
Vitesse linéaire et angulaire maximales envoyées au robot.
self.accuracy = np.array([0.01, 0.05])
Seuils en distance et en angle permettant de supposer que le robot à bien terminer son action.
#!/usr/bin/env python
import rospy
from geometry_msgs.msg import PoseStamped, Twist
from std_msgs.msg import Float32, Bool
from turtlesim.msg import Pose
import numpy as np
import time
import math
from tf.transformations import euler_from_quaternion
class To_move:
def __init__(self):
rospy.init_node('project', anonymous=True)
self.move_forward_publisher = rospy.Publisher('/move_forward',Float32, queue_size=10)
self.turn_left_publisher = rospy.Publisher('/turn_left',Float32, queue_size=10)
self.move_forward_subscriber = rospy.Subscriber('/move_forward_finished',Bool,self.callback_sub)
self.turn_left_subscriber = rospy.Subscriber('/turn_left_finished',Bool,self.callback_turn)
self.next_action =True
def callback_sub(self, msg):
#self.move_forward_publisher.publish(Float32(0.5))
self.next_action = True
print("move forword finished!")
def move2goal(self):
goal_pose = Pose()
goal_pose.x = input("entrez x ")
goal_pose.y = input("entrez y ")
distance = math.sqrt(goal_pose.x*goal_pose.x + goal_pose.y*goal_pose.y)
angle = math.atan(goal_pose.x/goal_pose.y)
while not rospy.is_shutdown():
time.sleep(1.0)
self.turn_left_publisher.publish(angle)
time.sleep(2.0)
self.move_forward_publisher.publish(distance)
def callback_turn(self, msg):
#self.turn_left_publisher.publish(Float32(3))
self.next_action = True
print("turn left finished!")
if __name__ == '__main__':
try:
x = To_move()
time.sleep(1.0)
x.move_forward_publisher.publish(Float32(0.5))
x.move2goal()
except rospy.ROSInterruptException:
pass
#!/usr/bin/env python
import rospy
from geometry_msgs.msg import PoseStamped, Twist
from std_msgs.msg import Float32, Bool
import numpy as np
from tf.transformations import euler_from_quaternion
class RobotMotion:
def __init__(self):
# Creates a node with name 'imu2pose' and make sure it is a
# unique node (using anonymous=True).
rospy.init_node('robot_motion', anonymous=True)
# Publisher which will publish to the topic '/cmd_vel'.
self.velocity_publisher = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
# Publisher which will publish to the topic '/move_forward_finished'.
self.move_forward_finished_publisher = rospy.Publisher('/move_forward_finished', Bool, queue_size=10)
# Publisher which will publish to the topic '/turn_left_finished'.
self.turn_left_finished_publisher = rospy.Publisher('/turn_left_finished', Bool, queue_size=10)
# A subscriber to the topic '/pose_odom'. self.update_pose is called
# when a message of type PoseStamped is received.
self.pose_subscriber = rospy.Subscriber('/pose_odom', PoseStamped, self.update_velocity)
# A subscriber to the topic '/move_forward'. self.move_forward is called
# when a message of type Float32 is received.
self.move_forward_subscriber = rospy.Subscriber('/move_forward', Float32, self.move_forward)
# A subscriber to the topic '/turn_left'. self.turn_left is called
# when a message of type Float32 is received.
self.turn_left_subscriber = rospy.Subscriber('/turn_left', Float32, self.turn_left)
self.pose = PoseStamped()
self.pose2d = np.array([0.0, 0.0, 0.0])
self.goal2d = np.array([0.0, 0.0, 0.0])
self.cmd_vel = Twist()
self.move_forward_flag = False
self.turn_left_flag = False
self.pose_observed = False
#self.next_action = False
# Parameters
self.K_p = np.array([1, 1])
self.max_speed = np.array([0.05, 0.5])
self.accuracy = np.array([0.01, 0.05])
# If we press control + C, the node will stop.
rospy.spin()
def move_forward(self, data):
# Move forward if data.data > 0 and backward if data.data < 0
if self.pose_observed:
self.goal2d[0:2] = self.pose2d[0:2] + np.array([data.data*np.cos(self.pose2d[2]), data.data*np.sin(self.pose2d[2])])
self.direction = np.array([np.cos(self.pose2d[2]), np.sin(self.pose2d[2])])
self.move_forward_flag = True
self.turn_left_flag = False
self.cmd_vel = Twist()
self.move_forward_finished_publisher.publish(Bool(False))
def turn_left(self, data):
# Turn left if data.data > 0 and right if data.data < 0
if self.pose_observed:
self.goal2d[0:2] = self.pose2d[0:2]
self.goal2d[2] = self.pose2d[2] + data.data
self.move_forward_flag = False
self.turn_left_flag = True
self.cmd_vel = Twist()
self.turn_left_finished_publisher.publish(Bool(False))
def update_velocity(self, data):
# Read the new pose and update the velocity command
self.pose2d = np.array([data.pose.position.x,
data.pose.position.y,
euler_from_quaternion([data.pose.orientation.x,
data.pose.orientation.y,
data.pose.orientation.z,
data.pose.orientation.w])[2]])
self.pose_observed = True
if self.turn_left_flag:
angle_error = self.goal2d[2] - self.pose2d[2]
if np.abs(angle_error) < self.accuracy[1]:
self.turn_left_flag = False
self.cmd_vel.angular.z = 0.
print 'turn left finished!'
self.turn_left_finished_publisher.publish(Bool(True))
else:
self.cmd_vel.angular.z = self.K_p[1] * angle_error
if np.abs(self.cmd_vel.angular.z) > self.max_speed[1]:
self.cmd_vel.angular.z = np.sign(self.cmd_vel.angular.z)*self.max_speed[1]
elif self.move_forward_flag:
distance_error = np.dot((self.goal2d[0:2] - self.pose2d[0:2]), self.direction)
if np.abs(distance_error) < self.accuracy[0]:
self.move_forward_flag = False
self.cmd_vel.linear.x = 0.
print 'move forward finished!'
self.move_forward_finished_publisher.publish(Bool(True))
else:
self.cmd_vel.linear.x = self.K_p[0] * distance_error
if np.abs(self.cmd_vel.linear.x) > self.max_speed[0]:
self.cmd_vel.linear.x = np.sign(self.cmd_vel.linear.x)*self.max_speed[0]
self.velocity_publisher.publish(self.cmd_vel)
if __name__ == '__main__':
try:
RobotMotion()
except rospy.ROSInterruptException:
pass
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment