first commit
This commit is contained in:
commit
221bc86dce
|
|
@ -0,0 +1,208 @@
|
||||||
|
cmake_minimum_required(VERSION 3.0.2)
|
||||||
|
project(ros_lab2)
|
||||||
|
|
||||||
|
## 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
|
||||||
|
roscpp
|
||||||
|
sensor_msgs
|
||||||
|
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
|
||||||
|
# sensor_msgs# 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 ros_lab2
|
||||||
|
# CATKIN_DEPENDS roscpp sensor_msgs 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}/ros_lab2.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/ros_lab2_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/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_ros_lab2.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)
|
||||||
|
add_executable(lab2 src/lab2.cpp)
|
||||||
|
target_link_libraries(lab2 ${catkin_LIBRARIES})
|
||||||
|
|
@ -0,0 +1,68 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<package format="2">
|
||||||
|
<name>ros_lab2</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>The ros_lab2 package</description>
|
||||||
|
|
||||||
|
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||||
|
<!-- Example: -->
|
||||||
|
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||||
|
<maintainer email="ros@todo.todo">ros</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/ros_lab2</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>roscpp</build_depend>
|
||||||
|
<build_depend>sensor_msgs</build_depend>
|
||||||
|
<build_depend>std_msgs</build_depend>
|
||||||
|
<build_export_depend>roscpp</build_export_depend>
|
||||||
|
<build_export_depend>sensor_msgs</build_export_depend>
|
||||||
|
<build_export_depend>std_msgs</build_export_depend>
|
||||||
|
<exec_depend>roscpp</exec_depend>
|
||||||
|
<exec_depend>sensor_msgs</exec_depend>
|
||||||
|
<exec_depend>std_msgs</exec_depend>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- The export tag contains other, unspecified, tags -->
|
||||||
|
<export>
|
||||||
|
<!-- Other tools can request additional information be placed here -->
|
||||||
|
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
|
|
@ -0,0 +1,133 @@
|
||||||
|
/// This program takes the coordinates of the turtlesim robot as input
|
||||||
|
/// and outputs a velocity command as a Twist message. The velocity command
|
||||||
|
/// will be calculated so as to get the turtlesim robot to move to a goal
|
||||||
|
/// x coordinate that can be any number from 0 to 11.
|
||||||
|
|
||||||
|
#include <cstdlib> // Use for the absolute value method abs()
|
||||||
|
#include <iostream> // Enables command line input and output
|
||||||
|
|
||||||
|
#include "ros/ros.h" // Necessary header files for ROS
|
||||||
|
#include "geometry_msgs/Twist.h" // Twist messages (linear & angular velocity)
|
||||||
|
#include "geometry_msgs/Pose2D.h" // x, y position and theta orientation
|
||||||
|
#include "turtlesim/Pose.h" // x, y, theta, linear & angular velocity
|
||||||
|
|
||||||
|
// Remove the need to use std:: prefix
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
// Key variable declarations
|
||||||
|
geometry_msgs::Twist velCommand; // Linear and angular velocity in m/s
|
||||||
|
geometry_msgs::Pose2D current; // Current x, y, and theta
|
||||||
|
geometry_msgs::Pose2D desired; // Desired x, y, and theta
|
||||||
|
|
||||||
|
// Goal x-value, which can be any number from 0 to 11 (inclusive)
|
||||||
|
const double GOAL = 1.3;
|
||||||
|
|
||||||
|
// The gain K, which is used to calculate the linear velocity
|
||||||
|
const double K_l = 1.0;
|
||||||
|
|
||||||
|
// The distance threshold in meters that will determine when
|
||||||
|
// the turtlesim robot successfully reaches the goal.
|
||||||
|
const double distanceTolerance = 0.1;
|
||||||
|
|
||||||
|
// Initialized variables and take care of other setup tasks
|
||||||
|
void setup() {
|
||||||
|
|
||||||
|
// Desired x goal coordinate
|
||||||
|
desired.x = GOAL;
|
||||||
|
|
||||||
|
// Initialize the Twist message.
|
||||||
|
// Initial linear and angular velocities are 0 m/s and rad/s, respectively.
|
||||||
|
velCommand.linear.x = 0.0;
|
||||||
|
velCommand.linear.y = 0.0;
|
||||||
|
velCommand.linear.z = 0.0;
|
||||||
|
velCommand.angular.x = 0.0;
|
||||||
|
velCommand.angular.y = 0.0;
|
||||||
|
velCommand.angular.z = 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get the distance between the current x coordinate and
|
||||||
|
// the desired x coordinate.
|
||||||
|
double getDistanceToGoal() {
|
||||||
|
return desired.x - current.x;
|
||||||
|
}
|
||||||
|
|
||||||
|
// If we haven't yet reached the goal, set the velocity value.
|
||||||
|
// Otherwise, stop the robot.
|
||||||
|
void setVelocity() {
|
||||||
|
if (abs(getDistanceToGoal()) > distanceTolerance) {
|
||||||
|
|
||||||
|
// The magnitude of the robot's velocity is directly
|
||||||
|
// proportional to the distance the robot is from the
|
||||||
|
// goal.
|
||||||
|
velCommand.linear.x = K_l * getDistanceToGoal();
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
cout << "Goal has been reached!" << endl << endl;
|
||||||
|
velCommand.linear.x = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// This callback function updates the current position and
|
||||||
|
// orientation of the robot.
|
||||||
|
void updatePose(const turtlesim::PoseConstPtr ¤tPose) {
|
||||||
|
current.x = currentPose->x;
|
||||||
|
current.y = currentPose->y;
|
||||||
|
current.theta = currentPose->theta;
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char **argv) {
|
||||||
|
|
||||||
|
setup();
|
||||||
|
|
||||||
|
// Initiate ROS
|
||||||
|
ros::init(argc, argv, "go_to_goal_x");
|
||||||
|
|
||||||
|
// Create the main access point to communicate with ROS
|
||||||
|
ros::NodeHandle node;
|
||||||
|
|
||||||
|
// Subscribe to the robot's pose
|
||||||
|
// Hold no messages in the queue. Automatically throw away
|
||||||
|
// any messages that are received that are not able to be
|
||||||
|
// processed quickly enough.
|
||||||
|
// Every time a new pose is received, update the robot's pose.
|
||||||
|
ros::Subscriber currentPoseSub =
|
||||||
|
node.subscribe("turtle1/pose", 0, updatePose);
|
||||||
|
|
||||||
|
// Publish velocity commands to a topic.
|
||||||
|
// Hold no messages in the queue. Automatically throw away
|
||||||
|
// any messages that are received that are not able to be
|
||||||
|
// processed quickly enough.
|
||||||
|
ros::Publisher velocityPub =
|
||||||
|
node.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 0);
|
||||||
|
|
||||||
|
// Specify a frequency that want the while loop below to loop at
|
||||||
|
// In this case, we want to loop 10 cycles per second
|
||||||
|
ros::Rate loop_rate(10);
|
||||||
|
|
||||||
|
// Keep running the while loop below as long as the ROS Master is active.
|
||||||
|
while (ros::ok()) {
|
||||||
|
|
||||||
|
// Here is where we call the callbacks that need to be called.
|
||||||
|
ros::spinOnce();
|
||||||
|
|
||||||
|
// After we call the callback function to update the robot's pose, we
|
||||||
|
// set the velocity values for the robot.
|
||||||
|
setVelocity();
|
||||||
|
|
||||||
|
// Publish the velocity command to the ROS topic
|
||||||
|
velocityPub.publish(velCommand);
|
||||||
|
|
||||||
|
// Print the output to the console
|
||||||
|
cout << "Current x = " << current.x << endl
|
||||||
|
<< "Desired x = " << desired.x << endl
|
||||||
|
<< "Distance to Goal = " << getDistanceToGoal() << " m" << endl
|
||||||
|
<< "Linear Velocity (x) = " << velCommand.linear.x << " m/s" << endl
|
||||||
|
<< endl;
|
||||||
|
|
||||||
|
// Sleep as long as we need to to make sure that we have a frequency of
|
||||||
|
// 10Hz
|
||||||
|
loop_rate.sleep();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
Loading…
Reference in New Issue