-
Notifications
You must be signed in to change notification settings - Fork 43
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
add gazebo movement test #409
base: master
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,18 +1,67 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
project(sub8_diagnostics) | ||
|
||
find_package(catkin REQUIRED COMPONENTS | ||
find_package(catkin | ||
REQUIRED COMPONENTS | ||
roscpp | ||
rospy | ||
mil_tools | ||
message_runtime | ||
sub8_msgs | ||
mil_msgs | ||
actionlib | ||
message_generation | ||
geometry_msgs | ||
sensor_msgs | ||
interactive_markers | ||
std_msgs | ||
actionlib_msgs | ||
mil_tools | ||
) | ||
|
||
catkin_python_setup() | ||
|
||
generate_messages( | ||
DEPENDENCIES std_msgs actionlib_msgs geometry_msgs sensor_msgs | ||
) | ||
|
||
|
||
# Any tools used to diagnose the core functionality of the sub should be put here | ||
catkin_package( | ||
INCLUDE_DIRS | ||
LIBRARIES | ||
CATKIN_DEPENDS | ||
actionlib | ||
message_runtime | ||
mil_msgs | ||
mil_tools | ||
roscpp | ||
sub8_msgs | ||
message_generation | ||
message_runtime | ||
geometry_msgs | ||
std_msgs | ||
actionlib_msgs | ||
DEPENDS | ||
mil_msgs | ||
) | ||
|
||
catkin_python_setup() | ||
|
||
|
||
|
||
|
||
|
||
|
||
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) | ||
|
||
add_executable(move_test src/move_test.cpp) | ||
|
||
target_link_libraries( | ||
move_test | ||
${catkin_LIBRARIES} | ||
) | ||
|
||
add_dependencies( | ||
move_test | ||
${mil_msgs_EXPORTED_TARGETS} | ||
) |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,72 @@ | ||
#include <ros/ros.h> | ||
#include <mil_msgs/MoveToActionResult.h> | ||
#include <mil_msgs/MoveToAction.h> | ||
#include <mil_msgs/MoveToActionGoal.h> | ||
#include <mil_msgs/MoveToGoal.h> | ||
#include <actionlib/client/simple_action_client.h> | ||
#include <stdio.h> | ||
#include <string> | ||
#include <iostream> | ||
|
||
using namespace std; | ||
|
||
// declares MoveToAction action client | ||
typedef actionlib::SimpleActionClient<mil_msgs::MoveToAction> MoveToActionClient; | ||
|
||
// first arg = forward command, second arg = up command | ||
int main(int argc, char** argv){ | ||
ros::init(argc, argv, "move_test"); | ||
|
||
// not sure what the server is called, figure out what the server is actually called | ||
MoveToActionClient ac("/moveto", true); | ||
|
||
while(!ac.waitForServer(ros::Duration(5.0))){ | ||
ROS_INFO("Waiting for the moveto server to come up!"); | ||
} | ||
|
||
string x = ""; | ||
string y = ""; | ||
|
||
if (argc < 2) { | ||
cout << "Error: No command found."; | ||
return 0; | ||
} | ||
|
||
// declares goal for the sub | ||
mil_msgs::MoveToGoal goal; | ||
x = string(argv[1]); | ||
|
||
goal.header.frame_id = "base_link"; | ||
goal.header.stamp = ros::Time::now(); | ||
|
||
// sets goal to x meter forward | ||
goal.posetwist.pose.position.x = atoi(argv[1]); | ||
goal.posetwist.pose.orientation.w = atoi(argv[1]); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why is orientation.w being set to the same as position.x? I'm having trouble seeing the usecase for that |
||
|
||
// sets goal to y meters upward if an arg is found | ||
if(argc == 3) { | ||
goal.posetwist.pose.position.y = atoi(argv[2]); | ||
x = string(argv[1]); | ||
y = string(argv[2]); | ||
} | ||
|
||
ROS_INFO("Sending goal"); | ||
|
||
ac.sendGoal(goal); | ||
ac.waitForResult(); | ||
|
||
// checks current robot state vs. goal state | ||
if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED){ | ||
cout << "The sub moved " + x + " meter(s) forward" << endl; | ||
if(argc == 3) { | ||
cout << "The sub moved " + y + " meter(s) up"; | ||
} | ||
} | ||
else { | ||
cout << "The sub failed to move forward " + x + " meter(s)" << endl; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Indention is all over here. Try |
||
if(argc == 3){ | ||
"The sub failed to move up " + y + " meters(s)"; | ||
} | ||
} | ||
return 0; | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Only some of these dependencies are actually needed (check the includes in your code). While adding more doesn't change program behavior, it does complicate the build process and make it more confusing to read