mirror of
https://github.com/EECS-467-W20-RRRobot-Project/RRRobot.git
synced 2025-08-22 16:12:45 +00:00
Added insert object test script
This commit is contained in:
34
rrrobot_ws/src/rrrobot/test/test_insert_object.cpp
Normal file
34
rrrobot_ws/src/rrrobot/test/test_insert_object.cpp
Normal file
@@ -0,0 +1,34 @@
|
|||||||
|
#include "rrrobot/model_insertion.h"
|
||||||
|
#include "ros/ros.h"
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
using std::cin;
|
||||||
|
using std::cout;
|
||||||
|
using std::endl;
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "insert_models");
|
||||||
|
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
|
||||||
|
ros::Publisher pub = nh.advertise<rrrobot::model_insertion>("/object_to_load", 1000);
|
||||||
|
|
||||||
|
while (ros::ok())
|
||||||
|
{
|
||||||
|
rrrobot::model_insertion msg;
|
||||||
|
cout << "Enter the model name: ";
|
||||||
|
cin >> msg.model_name;
|
||||||
|
cout << "Enter the pose: " << endl;
|
||||||
|
cout << "x: ";
|
||||||
|
cin >> msg.pose.position.x;
|
||||||
|
cout << "y: ";
|
||||||
|
cin >> msg.pose.position.y;
|
||||||
|
cout << "z: ";
|
||||||
|
cin >> msg.pose.position.z;
|
||||||
|
|
||||||
|
pub.publish(msg);
|
||||||
|
ros::spinOnce();
|
||||||
|
}
|
||||||
|
}
|
Reference in New Issue
Block a user