mirror of
https://github.com/EECS-467-W20-RRRobot-Project/RRRobot.git
synced 2025-08-15 06:18:32 +00:00
Test Insert Object Quit Option
- Add option to stop test insert object - Remove comments from model_insertion_plugin.cpp - Update home.md to specify root user when attaching a new terminal
This commit is contained in:
@@ -130,4 +130,4 @@ Instructions for working in the GEAR Simulation can be found on the [GEAR](gear.
|
|||||||
- See running containers
|
- See running containers
|
||||||
- `docker ps`
|
- `docker ps`
|
||||||
- Attach a new terminal to a running container
|
- Attach a new terminal to a running container
|
||||||
- `docker exec -it <container> bash`
|
- `docker exec -it -u root <container> bash`
|
||||||
|
@@ -20,9 +20,7 @@ public:
|
|||||||
{
|
{
|
||||||
std::cout << "Loading model insertion plugin" << std::endl;
|
std::cout << "Loading model insertion plugin" << std::endl;
|
||||||
|
|
||||||
// Option 1: Insert model from file via function call.
|
parent = _parent;
|
||||||
// The filename must be in the GAZEBO_MODEL_PATH environment variable.
|
|
||||||
parent = _parent; //->InsertModelFile("model://box");
|
|
||||||
|
|
||||||
if (!ros::isInitialized())
|
if (!ros::isInitialized())
|
||||||
{
|
{
|
||||||
@@ -63,8 +61,6 @@ public:
|
|||||||
|
|
||||||
// Send the message
|
// Send the message
|
||||||
factoryPub->Publish(to_pub);
|
factoryPub->Publish(to_pub);
|
||||||
|
|
||||||
// parent->InsertModelFile(std::string("model://") + msg.data);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@@ -18,8 +18,13 @@ int main(int argc, char **argv)
|
|||||||
while (ros::ok())
|
while (ros::ok())
|
||||||
{
|
{
|
||||||
rrrobot::model_insertion msg;
|
rrrobot::model_insertion msg;
|
||||||
cout << "Enter the model name: ";
|
cout << "Enter the model name (or 'q' to quit): ";
|
||||||
cin >> msg.model_name;
|
cin >> msg.model_name;
|
||||||
|
|
||||||
|
if (msg.model_name == "q") {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
cout << "Enter the pose: " << endl;
|
cout << "Enter the pose: " << endl;
|
||||||
cout << "x: ";
|
cout << "x: ";
|
||||||
cin >> msg.pose.position.x;
|
cin >> msg.pose.position.x;
|
||||||
|
Reference in New Issue
Block a user