Skip to content
Snippets Groups Projects
Commit 63f6111d authored by Paul Beuchat's avatar Paul Beuchat
Browse files

Small adjustments for the teacher node to get the namespaces aligned

parent 30b0edad
No related branches found
No related tags found
No related merge requests found
...@@ -871,7 +871,7 @@ void MainGUIWindow::on_save_in_DB_button_clicked() ...@@ -871,7 +871,7 @@ void MainGUIWindow::on_save_in_DB_button_clicked()
tmp_entry.crazyflieContext.localArea.ymax = y_max * FROM_UNITS_TO_METERS; tmp_entry.crazyflieContext.localArea.ymax = y_max * FROM_UNITS_TO_METERS;
tmp_entry.crazyflieContext.localArea.zmin = -0.2; tmp_entry.crazyflieContext.localArea.zmin = -0.2;
tmp_entry.crazyflieContext.localArea.zmax = 1.2; tmp_entry.crazyflieContext.localArea.zmax = 2.2;
} }
} }
tmp_db.crazyflieEntries.push_back(tmp_entry); tmp_db.crazyflieEntries.push_back(tmp_entry);
......
...@@ -75,12 +75,14 @@ bool rosNodeThread::init() ...@@ -75,12 +75,14 @@ bool rosNodeThread::init()
ros::Time::init(); ros::Time::init();
ros::NodeHandle nh("~"); ros::NodeHandle nh("~");
m_vicon_subscriber = nh.subscribe("/ViconDataPublisher/ViconData", 100, &rosNodeThread::messageCallback, this); ros::NodeHandle nodeHandle_dfall_root("/dfall");
m_vicon_subscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, &rosNodeThread::messageCallback, this);
// clients for db services: // clients for db services:
m_read_db_client = nh.serviceClient<CMRead>("/CentralManagerService/Read", false); m_read_db_client = nodeHandle_dfall_root.serviceClient<CMRead>("CentralManagerService/Read", false);
m_update_db_client = nh.serviceClient<CMUpdate>("/CentralManagerService/Update", false); m_update_db_client = nodeHandle_dfall_root.serviceClient<CMUpdate>("CentralManagerService/Update", false);
m_command_db_client = nh.serviceClient<CMCommand>("/CentralManagerService/Command", false); m_command_db_client = nodeHandle_dfall_root.serviceClient<CMCommand>("CentralManagerService/Command", false);
m_pThread->start(); m_pThread->start();
return true; return true;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment