Skip to content
Snippets Groups Projects
Commit ae6e1a26 authored by Johannes Mey's avatar Johannes Mey
Browse files

change default node name for debug purposes

parent 13073468
No related branches found
No related tags found
No related merge requests found
......@@ -18,7 +18,7 @@
#include "ccf/connection/MqttConnection.h"
#include "ccf/util/NodeUtil.h"
std::string NODE_NAME = "ceti_cell_placeworld";
std::string NODE_NAME = "ceti_cell_empty";
using CetiRosToolbox::getParameter;
using CetiRosToolbox::getPrivateParameter;
......@@ -41,7 +41,7 @@ int main(int argc, char** argv)
std::unique_ptr<MqttConnection> mqtt_connection =
std::make_unique<MqttConnection>(mqttServer, ros::this_node::getName());
mqtt_connection->listen(getParameter<std::string>(n, "topics/selection", "selection"));
auto commandTopic = getParameter<std::string>(n, "topics/command", "/ceti_cell_placeworld/command");
auto commandTopic = getParameter<std::string>(n, "topics/command", NODE_NAME + "/command");
mqtt_connection->listen(commandTopic);
auto other_cell_topic = getPrivateParameter<std::string>("other_cell", "/ceti_cell_2_placeworld/scene/delta-update");
mqtt_connection->listen(other_cell_topic);
......@@ -76,20 +76,19 @@ int main(int argc, char** argv)
});
auto pick_place_callback = [&controller](const Command& command) {
const PickAndPlace& pick_place = command.pickandplace();
if (command.has_pickandplace())
{
ROS_INFO_STREAM("[COMMAND] for robot " << pick_place.idrobot() << ": Pick object " << pick_place.idpick() << " and place it at " << pick_place.idplace());
Object* pick_object = controller.resolveObject(pick_place.idpick());
if (!pick_object)
{
ROS_ERROR_STREAM("[COMMAND] FAILED! Selected unknown pick object '" << pick_place.idpick() << "'");
ROS_ERROR_STREAM("[COMMAND] FAILED! Selected unknown pick object '" << command.pickandplace().idpick() << "'");
return;
}
Object* place_object = controller.resolveObject(pick_place.idplace());
Object* place_object = controller.resolveObject(command.pickandplace().idplace());
if (!place_object)
{
ROS_ERROR_STREAM("[COMMAND] FAILED! Selected unknown place object '" << pick_place.idplace() << "'");
ROS_ERROR_STREAM("[COMMAND] FAILED! Selected unknown place object '" << command.pickandplace().idplace() << "'");
return;
}
if (pick_object->type() != Object::BOX)
......@@ -119,11 +118,11 @@ int main(int argc, char** argv)
{
if (!controller.pickAndDrop(*robot, *pick_object, *place_object, false))
{
ROS_WARN_STREAM("[COMMAND] FAILED! Unable to remove box '" << pick_place.idpick() << "'!");
ROS_WARN_STREAM("[COMMAND] FAILED! Unable to remove box '" << command.pickandplace().idpick() << "'!");
}
else
{
ROS_INFO_STREAM("[COMMAND] SUCCESS! '" << pick_place.idpick() << "' is no more.");
ROS_INFO_STREAM("[COMMAND] SUCCESS! '" << command.pickandplace().idpick() << "' is no more.");
controller.sendScene();
}
}
......@@ -131,11 +130,11 @@ int main(int argc, char** argv)
{
if (!controller.pickAndPlace(*robot, *pick_object, *place_object, false))
{
ROS_WARN_STREAM("[COMMAND] FAILED! Unable to move box '" << pick_place.idpick() << "'!");
ROS_WARN_STREAM("[COMMAND] FAILED! Unable to move box '" << command.pickandplace().idpick() << "'!");
}
else
{
ROS_INFO_STREAM("[COMMAND] SUCCESS! " << pick_place.idpick() << "' is at its new location.");
ROS_INFO_STREAM("[COMMAND] SUCCESS! " << command.pickandplace().idpick() << "' is at its new location.");
controller.sendScene();
}
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment