47 loader_.robotTreeWidget,SIGNAL(itemClicked(QTreeWidgetItem *,
int)),
111 loader_.loadRobotButton,SIGNAL(clicked(
bool)),
156 for(
int i = laserCount - 1 ; i >= 0 ; i--)
158 for(
int i = sonarCount - 1 ; i >= 0 ; i--)
160 for(
int i = rfidCount - 1 ; i >= 0 ; i--)
162 for(
int i = co2SensorsCount - 1 ; i >= 0 ; i--)
164 for(
int i = thermalSensorsCount - 1 ; i >= 0 ; i--)
166 for(
int i = soundSensorsCount - 1 ; i >= 0 ; i--)
168 for(
int i = footprintCount - 1 ; i >= 0 ; i--)
171 CRobotCreatorConnector::laser_number = 0;
172 CRobotCreatorConnector::sonar_number = 0;
173 CRobotCreatorConnector::rfid_number = 0;
174 CRobotCreatorConnector::co2_sensors_number = 0;
175 CRobotCreatorConnector::thermal_sensors_number = 0;
176 CRobotCreatorConnector::sound_sensors_number = 0;
190 QTreeWidgetItem * item,
197 unsigned int laserFrameId =
searchLaser(item->text(0));
198 if(laserFrameId == -1)
200 ROS_ERROR(
"Something went terribly wrong...");
212 unsigned int sonarFrameId =
searchSonar(item->text(0));
213 if(sonarFrameId == -1)
215 ROS_ERROR(
"Something went terribly wrong...");
227 unsigned int frameId =
searchRfid(item->text(0));
230 ROS_ERROR(
"Something went terribly wrong...");
245 ROS_ERROR(
"Something went terribly wrong...");
260 ROS_ERROR(
"Something went terribly wrong...");
275 ROS_ERROR(
"Something went terribly wrong...");
480 QTreeWidgetItem *new_point;
482 new_point =
new QTreeWidgetItem();
484 new_point->setText(0,QString(
"[") + QString().setNum(pt.x) + QString(
",") +
485 QString().setNum(pt.y) + QString(
"]"));
501 geometry_msgs::Point pt;
507 QTreeWidgetItem *new_point;
509 new_point =
new QTreeWidgetItem();
511 new_point->setText(0,QString(
"[0,0]"));
548 float x = xstr.toFloat();
549 float y = ystr.toFloat();
569 ystr + QString(
"]"));
610 float x = xstr.toFloat();
611 float y = ystr.toFloat();
631 ystr + QString(
"]"));
642 QString laserFrameId=QString(
"laser_") +
643 QString().setNum(++CRobotCreatorConnector::laser_number);
645 stdr_msgs::LaserSensorMsg lmsg;
646 lmsg.frame_id = laserFrameId.toStdString();
649 lmsg.minAngle = - 135;
655 lmsg.noise.noiseMean = 0;
656 lmsg.noise.noiseStd = 0;
657 lmsg.frequency = 10.0;
661 QTreeWidgetItem *lnode;
662 lnode =
new QTreeWidgetItem();
663 lnode->setText(0,laserFrameId);
681 rays =
new QTreeWidgetItem();
682 angleSpan =
new QTreeWidgetItem();
683 orientation =
new QTreeWidgetItem();
684 maxRange =
new QTreeWidgetItem();
685 minRange =
new QTreeWidgetItem();
686 noiseMean =
new QTreeWidgetItem();
687 noiseStd =
new QTreeWidgetItem();
688 poseX =
new QTreeWidgetItem();
689 poseY =
new QTreeWidgetItem();
690 frequency =
new QTreeWidgetItem();
692 rays->setText(0,QString(
"Number of rays"));
693 angleSpan->setText(0,QString(
"Angle span"));
694 orientation->setText(0,QString(
"Orientation"));
695 maxRange->setText(0,QString(
"Max range"));
696 minRange->setText(0,QString(
"Min range"));
697 noiseMean->setText(0,QString(
"Noise mean"));
698 noiseStd->setText(0,QString(
"Noise std"));
699 poseX->setText(0,QString(
"Pose - x"));
700 poseY->setText(0,QString(
"Pose - y"));
701 frequency->setText(0,QString(
"Frequency"));
703 rays->setText(1,QString().setNum(lmsg.numRays));
704 angleSpan->setText(1,QString().setNum(lmsg.maxAngle - lmsg.minAngle));
705 orientation->setText(1,QString().setNum(lmsg.maxAngle + lmsg.minAngle));
706 maxRange->setText(1,QString().setNum(lmsg.maxRange));
707 minRange->setText(1,QString().setNum(lmsg.minRange));
708 noiseMean->setText(1,QString().setNum(lmsg.noise.noiseMean));
709 noiseStd->setText(1,QString().setNum(lmsg.noise.noiseStd));
710 poseX->setText(1,QString().setNum(lmsg.pose.x));
711 poseY->setText(1,QString().setNum(lmsg.pose.y));
712 frequency->setText(1,QString().setNum(lmsg.frequency));
714 lnode->addChild(rays);
715 lnode->addChild(angleSpan);
716 lnode->addChild(orientation);
717 lnode->addChild(maxRange);
718 lnode->addChild(minRange);
719 lnode->addChild(noiseMean);
720 lnode->addChild(noiseStd);
721 lnode->addChild(poseX);
722 lnode->addChild(poseY);
723 lnode->addChild(frequency);
727 lnode->setExpanded(
false);
739 CRobotCreatorConnector::laser_number++;
740 QString laserFrameId=QString(lmsg.frame_id.c_str());
742 QTreeWidgetItem *lnode;
743 lnode =
new QTreeWidgetItem();
744 lnode->setText(0,laserFrameId);
762 rays =
new QTreeWidgetItem();
763 angleSpan =
new QTreeWidgetItem();
764 orientation =
new QTreeWidgetItem();
765 maxRange =
new QTreeWidgetItem();
766 minRange =
new QTreeWidgetItem();
767 noiseMean =
new QTreeWidgetItem();
768 noiseStd =
new QTreeWidgetItem();
769 poseX =
new QTreeWidgetItem();
770 poseY =
new QTreeWidgetItem();
771 frequency =
new QTreeWidgetItem();
773 rays->setText(0,QString(
"Number of rays"));
774 angleSpan->setText(0,QString(
"Angle span"));
775 orientation->setText(0,QString(
"Orientation"));
776 maxRange->setText(0,QString(
"Max range"));
777 minRange->setText(0,QString(
"Min range"));
778 noiseMean->setText(0,QString(
"Noise mean"));
779 noiseStd->setText(0,QString(
"Noise std"));
780 poseX->setText(0,QString(
"Pose - x"));
781 poseY->setText(0,QString(
"Pose - y"));
782 frequency->setText(0,QString(
"Frequency"));
784 rays->setText(1,QString().setNum(lmsg.numRays));
785 angleSpan->setText(1,QString().setNum(lmsg.maxAngle - lmsg.minAngle));
786 orientation->setText(1,QString().setNum(lmsg.pose.theta));
787 maxRange->setText(1,QString().setNum(lmsg.maxRange));
788 minRange->setText(1,QString().setNum(lmsg.minRange));
789 noiseMean->setText(1,QString().setNum(lmsg.noise.noiseMean));
790 noiseStd->setText(1,QString().setNum(lmsg.noise.noiseStd));
791 poseX->setText(1,QString().setNum(lmsg.pose.x));
792 poseY->setText(1,QString().setNum(lmsg.pose.y));
793 frequency->setText(1,QString().setNum(lmsg.frequency));
795 lnode->addChild(rays);
796 lnode->addChild(angleSpan);
797 lnode->addChild(orientation);
798 lnode->addChild(maxRange);
799 lnode->addChild(minRange);
800 lnode->addChild(noiseMean);
801 lnode->addChild(noiseStd);
802 lnode->addChild(poseX);
803 lnode->addChild(poseY);
804 lnode->addChild(frequency);
808 lnode->setExpanded(
false);
818 QString sonarFrameId =
820 QString().setNum(++CRobotCreatorConnector::sonar_number);
822 stdr_msgs::SonarSensorMsg smsg;
823 smsg.frame_id = sonarFrameId.toStdString();
826 smsg.coneAngle = 50.0;
830 smsg.noise.noiseMean = 0;
831 smsg.noise.noiseStd = 0;
836 QTreeWidgetItem *snode;
837 snode =
new QTreeWidgetItem();
838 snode->setText(0,sonarFrameId);
855 coneAngle =
new QTreeWidgetItem();
856 orientation =
new QTreeWidgetItem();
857 maxRange =
new QTreeWidgetItem();
858 minRange =
new QTreeWidgetItem();
859 noiseMean =
new QTreeWidgetItem();
860 noiseStd =
new QTreeWidgetItem();
861 poseX =
new QTreeWidgetItem();
862 poseY =
new QTreeWidgetItem();
863 frequency =
new QTreeWidgetItem();
865 coneAngle->setText(0,QString(
"Cone span"));
866 orientation->setText(0,QString(
"Orientation"));
867 maxRange->setText(0,QString(
"Max range"));
868 minRange->setText(0,QString(
"Min range"));
869 noiseMean->setText(0,QString(
"Noise mean"));
870 noiseStd->setText(0,QString(
"Noise std"));
871 poseX->setText(0,QString(
"Pose - x"));
872 poseY->setText(0,QString(
"Pose - y"));
873 frequency->setText(0,QString(
"Frequency"));
875 coneAngle->setText(1,QString().setNum(smsg.coneAngle));
876 orientation->setText(1,QString().setNum(smsg.pose.theta));
877 maxRange->setText(1,QString().setNum(smsg.maxRange));
878 minRange->setText(1,QString().setNum(smsg.minRange));
879 noiseMean->setText(1,QString().setNum(smsg.noise.noiseMean));
880 noiseStd->setText(1,QString().setNum(smsg.noise.noiseStd));
881 poseX->setText(1,QString().setNum(smsg.pose.x));
882 poseY->setText(1,QString().setNum(smsg.pose.y));
883 frequency->setText(1,QString().setNum(smsg.frequency));
885 snode->addChild(coneAngle);
886 snode->addChild(orientation);
887 snode->addChild(maxRange);
888 snode->addChild(minRange);
889 snode->addChild(noiseMean);
890 snode->addChild(noiseStd);
891 snode->addChild(poseX);
892 snode->addChild(poseY);
893 snode->addChild(frequency);
897 snode->setExpanded(
false);
909 CRobotCreatorConnector::sonar_number++;
910 QString sonarFrameId = QString(smsg.frame_id.c_str());
912 QTreeWidgetItem *snode;
913 snode =
new QTreeWidgetItem();
914 snode->setText(0,sonarFrameId);
931 coneAngle =
new QTreeWidgetItem();
932 orientation =
new QTreeWidgetItem();
933 maxRange =
new QTreeWidgetItem();
934 minRange =
new QTreeWidgetItem();
935 noiseMean =
new QTreeWidgetItem();
936 noiseStd =
new QTreeWidgetItem();
937 poseX =
new QTreeWidgetItem();
938 poseY =
new QTreeWidgetItem();
939 frequency =
new QTreeWidgetItem();
941 coneAngle->setText(0,QString(
"Cone span"));
942 orientation->setText(0,QString(
"Orientation"));
943 maxRange->setText(0,QString(
"Max range"));
944 minRange->setText(0,QString(
"Min range"));
945 noiseMean->setText(0,QString(
"Noise mean"));
946 noiseStd->setText(0,QString(
"Noise std"));
947 poseX->setText(0,QString(
"Pose - x"));
948 poseY->setText(0,QString(
"Pose - y"));
949 frequency->setText(0,QString(
"Frequency"));
951 coneAngle->setText(1,QString().setNum(smsg.coneAngle));
952 orientation->setText(1,QString().setNum(smsg.pose.theta));
953 maxRange->setText(1,QString().setNum(smsg.maxRange));
954 minRange->setText(1,QString().setNum(smsg.minRange));
955 noiseMean->setText(1,QString().setNum(smsg.noise.noiseMean));
956 noiseStd->setText(1,QString().setNum(smsg.noise.noiseStd));
957 poseX->setText(1,QString().setNum(smsg.pose.x));
958 poseY->setText(1,QString().setNum(smsg.pose.y));
959 frequency->setText(1,QString().setNum(smsg.frequency));
961 snode->addChild(coneAngle);
962 snode->addChild(orientation);
963 snode->addChild(maxRange);
964 snode->addChild(minRange);
965 snode->addChild(noiseMean);
966 snode->addChild(noiseStd);
967 snode->addChild(poseX);
968 snode->addChild(poseY);
969 snode->addChild(frequency);
973 snode->setExpanded(
false);
983 QString rfidFrameId=QString(
"rfid_reader_") +
984 QString().setNum(CRobotCreatorConnector::rfid_number++);
986 stdr_msgs::RfidSensorMsg smsg;
987 smsg.frame_id = rfidFrameId.toStdString();
989 smsg.angleSpan = 360.0;
993 smsg.signalCutoff = 0;
998 QTreeWidgetItem *snode;
999 snode =
new QTreeWidgetItem();
1000 snode->setText(0,rfidFrameId);
1015 angleSpan =
new QTreeWidgetItem();
1016 orientation =
new QTreeWidgetItem();
1017 maxRange =
new QTreeWidgetItem();
1018 poseX =
new QTreeWidgetItem();
1019 poseY =
new QTreeWidgetItem();
1020 signalCutoff =
new QTreeWidgetItem();
1021 frequency =
new QTreeWidgetItem();
1023 angleSpan->setText(0,QString(
"Angle span"));
1024 orientation->setText(0,QString(
"Orientation"));
1025 maxRange->setText(0,QString(
"Max range"));
1026 poseX->setText(0,QString(
"Pose - x"));
1027 poseY->setText(0,QString(
"Pose - y"));
1028 signalCutoff->setText(0,QString(
"Signal cutoff"));
1029 frequency->setText(0,QString(
"Frequency"));
1031 angleSpan->setText(1,QString().setNum(smsg.angleSpan));
1032 orientation->setText(1,QString().setNum(smsg.pose.theta));
1033 maxRange->setText(1,QString().setNum(smsg.maxRange));
1034 poseX->setText(1,QString().setNum(smsg.pose.x));
1035 poseY->setText(1,QString().setNum(smsg.pose.y));
1036 signalCutoff->setText(1,QString().setNum(smsg.signalCutoff));
1037 frequency->setText(1,QString().setNum(smsg.frequency));
1039 snode->addChild(angleSpan);
1040 snode->addChild(orientation);
1041 snode->addChild(maxRange);
1042 snode->addChild(poseX);
1043 snode->addChild(poseY);
1044 snode->addChild(signalCutoff);
1045 snode->addChild(frequency);
1049 snode->setExpanded(
false);
1058 QString co2SensorFrameId=QString(
"co2_sensor_") +
1059 QString().setNum(CRobotCreatorConnector::co2_sensors_number++);
1061 stdr_msgs::CO2SensorMsg smsg;
1062 smsg.frame_id = co2SensorFrameId.toStdString();
1063 smsg.maxRange = 3.0;
1067 smsg.pose.theta = 0;
1069 smsg.frequency = 10;
1073 QTreeWidgetItem *snode;
1074 snode =
new QTreeWidgetItem();
1075 snode->setText(0,co2SensorFrameId);
1091 orientation =
new QTreeWidgetItem();
1092 maxRange =
new QTreeWidgetItem();
1093 poseX =
new QTreeWidgetItem();
1094 poseY =
new QTreeWidgetItem();
1096 frequency =
new QTreeWidgetItem();
1099 orientation->setText(0,QString(
"Orientation"));
1100 maxRange->setText(0,QString(
"Max range"));
1101 poseX->setText(0,QString(
"Pose - x"));
1102 poseY->setText(0,QString(
"Pose - y"));
1104 frequency->setText(0,QString(
"Frequency"));
1107 orientation->setText(1,QString().setNum(smsg.pose.theta));
1108 maxRange->setText(1,QString().setNum(smsg.maxRange));
1109 poseX->setText(1,QString().setNum(smsg.pose.x));
1110 poseY->setText(1,QString().setNum(smsg.pose.y));
1112 frequency->setText(1,QString().setNum(smsg.frequency));
1115 snode->addChild(orientation);
1116 snode->addChild(maxRange);
1117 snode->addChild(poseX);
1118 snode->addChild(poseY);
1120 snode->addChild(frequency);
1124 snode->setExpanded(
false);
1133 QString thermalSensorFrameId=QString(
"thermal_sensor_") +
1134 QString().setNum(CRobotCreatorConnector::thermal_sensors_number++);
1136 stdr_msgs::ThermalSensorMsg smsg;
1137 smsg.frame_id = thermalSensorFrameId.toStdString();
1138 smsg.maxRange = 3.0;
1139 smsg.angleSpan = 20.0;
1142 smsg.pose.theta = 0;
1144 smsg.frequency = 10;
1148 QTreeWidgetItem *snode;
1149 snode =
new QTreeWidgetItem();
1150 snode->setText(0,thermalSensorFrameId);
1165 angleSpan =
new QTreeWidgetItem();
1166 orientation =
new QTreeWidgetItem();
1167 maxRange =
new QTreeWidgetItem();
1168 poseX =
new QTreeWidgetItem();
1169 poseY =
new QTreeWidgetItem();
1171 frequency =
new QTreeWidgetItem();
1173 angleSpan->setText(0,QString(
"Angle span"));
1174 orientation->setText(0,QString(
"Orientation"));
1175 maxRange->setText(0,QString(
"Max range"));
1176 poseX->setText(0,QString(
"Pose - x"));
1177 poseY->setText(0,QString(
"Pose - y"));
1179 frequency->setText(0,QString(
"Frequency"));
1181 angleSpan->setText(1,QString().setNum(smsg.angleSpan));
1182 orientation->setText(1,QString().setNum(smsg.pose.theta));
1183 maxRange->setText(1,QString().setNum(smsg.maxRange));
1184 poseX->setText(1,QString().setNum(smsg.pose.x));
1185 poseY->setText(1,QString().setNum(smsg.pose.y));
1187 frequency->setText(1,QString().setNum(smsg.frequency));
1189 snode->addChild(angleSpan);
1190 snode->addChild(orientation);
1191 snode->addChild(maxRange);
1192 snode->addChild(poseX);
1193 snode->addChild(poseY);
1195 snode->addChild(frequency);
1199 snode->setExpanded(
false);
1208 QString soundSensorFrameId=QString(
"sound_sensor_") +
1209 QString().setNum(CRobotCreatorConnector::sound_sensors_number++);
1211 stdr_msgs::SoundSensorMsg smsg;
1212 smsg.frame_id = soundSensorFrameId.toStdString();
1213 smsg.maxRange = 3.0;
1214 smsg.angleSpan = 180.0;
1217 smsg.pose.theta = 0;
1219 smsg.frequency = 10;
1223 QTreeWidgetItem *snode;
1224 snode =
new QTreeWidgetItem();
1225 snode->setText(0,soundSensorFrameId);
1240 angleSpan =
new QTreeWidgetItem();
1241 orientation =
new QTreeWidgetItem();
1242 maxRange =
new QTreeWidgetItem();
1243 poseX =
new QTreeWidgetItem();
1244 poseY =
new QTreeWidgetItem();
1246 frequency =
new QTreeWidgetItem();
1248 angleSpan->setText(0,QString(
"Angle span"));
1249 orientation->setText(0,QString(
"Orientation"));
1250 maxRange->setText(0,QString(
"Max range"));
1251 poseX->setText(0,QString(
"Pose - x"));
1252 poseY->setText(0,QString(
"Pose - y"));
1254 frequency->setText(0,QString(
"Frequency"));
1256 angleSpan->setText(1,QString().setNum(smsg.angleSpan));
1257 orientation->setText(1,QString().setNum(smsg.pose.theta));
1258 maxRange->setText(1,QString().setNum(smsg.maxRange));
1259 poseX->setText(1,QString().setNum(smsg.pose.x));
1260 poseY->setText(1,QString().setNum(smsg.pose.y));
1262 frequency->setText(1,QString().setNum(smsg.frequency));
1264 snode->addChild(angleSpan);
1265 snode->addChild(orientation);
1266 snode->addChild(maxRange);
1267 snode->addChild(poseX);
1268 snode->addChild(poseY);
1270 snode->addChild(frequency);
1274 snode->setExpanded(
false);
1285 CRobotCreatorConnector::rfid_number++;
1286 QString rfidFrameId=QString(smsg.frame_id.c_str());
1288 QTreeWidgetItem *snode;
1289 snode =
new QTreeWidgetItem();
1290 snode->setText(0,rfidFrameId);
1305 angleSpan =
new QTreeWidgetItem();
1306 orientation =
new QTreeWidgetItem();
1307 maxRange =
new QTreeWidgetItem();
1308 poseX =
new QTreeWidgetItem();
1309 poseY =
new QTreeWidgetItem();
1310 signalCutoff =
new QTreeWidgetItem();
1311 frequency =
new QTreeWidgetItem();
1313 angleSpan->setText(0,QString(
"Angle span"));
1314 orientation->setText(0,QString(
"Orientation"));
1315 maxRange->setText(0,QString(
"Max range"));
1316 poseX->setText(0,QString(
"Pose - x"));
1317 poseY->setText(0,QString(
"Pose - y"));
1318 signalCutoff->setText(0,QString(
"Signal cutoff"));
1319 frequency->setText(0,QString(
"Frequency"));
1321 angleSpan->setText(1,QString().setNum(smsg.angleSpan));
1322 orientation->setText(1,QString().setNum(smsg.pose.theta));
1323 maxRange->setText(1,QString().setNum(smsg.maxRange));
1324 poseX->setText(1,QString().setNum(smsg.pose.x));
1325 poseY->setText(1,QString().setNum(smsg.pose.y));
1326 signalCutoff->setText(1,QString().setNum(smsg.signalCutoff));
1327 frequency->setText(1,QString().setNum(smsg.frequency));
1329 snode->addChild(angleSpan);
1330 snode->addChild(orientation);
1331 snode->addChild(maxRange);
1332 snode->addChild(poseX);
1333 snode->addChild(poseY);
1334 snode->addChild(signalCutoff);
1335 snode->addChild(frequency);
1339 snode->setExpanded(
false);
1349 CRobotCreatorConnector::co2_sensors_number++;
1350 QString co2SensorFrameId=QString(smsg.frame_id.c_str());
1352 QTreeWidgetItem *snode;
1353 snode =
new QTreeWidgetItem();
1354 snode->setText(0,co2SensorFrameId);
1370 orientation =
new QTreeWidgetItem();
1371 maxRange =
new QTreeWidgetItem();
1372 poseX =
new QTreeWidgetItem();
1373 poseY =
new QTreeWidgetItem();
1375 frequency =
new QTreeWidgetItem();
1378 orientation->setText(0,QString(
"Orientation"));
1379 maxRange->setText(0,QString(
"Max range"));
1380 poseX->setText(0,QString(
"Pose - x"));
1381 poseY->setText(0,QString(
"Pose - y"));
1383 frequency->setText(0,QString(
"Frequency"));
1386 orientation->setText(1,QString().setNum(smsg.pose.theta));
1387 maxRange->setText(1,QString().setNum(smsg.maxRange));
1388 poseX->setText(1,QString().setNum(smsg.pose.x));
1389 poseY->setText(1,QString().setNum(smsg.pose.y));
1391 frequency->setText(1,QString().setNum(smsg.frequency));
1394 snode->addChild(orientation);
1395 snode->addChild(maxRange);
1396 snode->addChild(poseX);
1397 snode->addChild(poseY);
1399 snode->addChild(frequency);
1403 snode->setExpanded(
false);
1413 CRobotCreatorConnector::thermal_sensors_number++;
1414 QString thermalSensorFrameId=QString(smsg.frame_id.c_str());
1416 QTreeWidgetItem *snode;
1417 snode =
new QTreeWidgetItem();
1418 snode->setText(0,thermalSensorFrameId);
1433 angleSpan =
new QTreeWidgetItem();
1434 orientation =
new QTreeWidgetItem();
1435 maxRange =
new QTreeWidgetItem();
1436 poseX =
new QTreeWidgetItem();
1437 poseY =
new QTreeWidgetItem();
1439 frequency =
new QTreeWidgetItem();
1441 angleSpan->setText(0,QString(
"Angle span"));
1442 orientation->setText(0,QString(
"Orientation"));
1443 maxRange->setText(0,QString(
"Max range"));
1444 poseX->setText(0,QString(
"Pose - x"));
1445 poseY->setText(0,QString(
"Pose - y"));
1447 frequency->setText(0,QString(
"Frequency"));
1449 angleSpan->setText(1,QString().setNum(smsg.angleSpan));
1450 orientation->setText(1,QString().setNum(smsg.pose.theta));
1451 maxRange->setText(1,QString().setNum(smsg.maxRange));
1452 poseX->setText(1,QString().setNum(smsg.pose.x));
1453 poseY->setText(1,QString().setNum(smsg.pose.y));
1455 frequency->setText(1,QString().setNum(smsg.frequency));
1457 snode->addChild(angleSpan);
1458 snode->addChild(orientation);
1459 snode->addChild(maxRange);
1460 snode->addChild(poseX);
1461 snode->addChild(poseY);
1463 snode->addChild(frequency);
1467 snode->setExpanded(
false);
1477 CRobotCreatorConnector::sound_sensors_number++;
1478 QString soundSensorFrameId=QString(smsg.frame_id.c_str());
1480 QTreeWidgetItem *snode;
1481 snode =
new QTreeWidgetItem();
1482 snode->setText(0,soundSensorFrameId);
1497 angleSpan =
new QTreeWidgetItem();
1498 orientation =
new QTreeWidgetItem();
1499 maxRange =
new QTreeWidgetItem();
1500 poseX =
new QTreeWidgetItem();
1501 poseY =
new QTreeWidgetItem();
1503 frequency =
new QTreeWidgetItem();
1505 angleSpan->setText(0,QString(
"Angle span"));
1506 orientation->setText(0,QString(
"Orientation"));
1507 maxRange->setText(0,QString(
"Max range"));
1508 poseX->setText(0,QString(
"Pose - x"));
1509 poseY->setText(0,QString(
"Pose - y"));
1511 frequency->setText(0,QString(
"Frequency"));
1513 angleSpan->setText(1,QString().setNum(smsg.angleSpan));
1514 orientation->setText(1,QString().setNum(smsg.pose.theta));
1515 maxRange->setText(1,QString().setNum(smsg.maxRange));
1516 poseX->setText(1,QString().setNum(smsg.pose.x));
1517 poseY->setText(1,QString().setNum(smsg.pose.y));
1519 frequency->setText(1,QString().setNum(smsg.frequency));
1521 snode->addChild(angleSpan);
1522 snode->addChild(orientation);
1523 snode->addChild(maxRange);
1524 snode->addChild(poseX);
1525 snode->addChild(poseY);
1527 snode->addChild(frequency);
1531 snode->setExpanded(
false);
1543 unsigned int laserFrameId =
searchLaser(item->text(0));
1544 if(laserFrameId == -1)
1561 unsigned int sonarFrameId =
searchSonar(item->text(0));
1562 if(sonarFrameId == -1)
1579 unsigned int rfidFrameId =
searchRfid(item->text(0));
1580 if(rfidFrameId == -1)
1662 QApplication::translate(
1664 item->text(0).toStdString().c_str(),
1666 QApplication::UnicodeUTF8));
1680 unsigned int laserFrameId =
searchLaser(item->text(0));
1681 if(laserFrameId == -1)
1686 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].numRays));
1689 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].maxRange));
1692 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].minRange));
1700 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].pose.theta));
1711 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].pose.x));
1714 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].pose.y));
1717 QString().setNum(
new_robot_msg_.laserSensors[laserFrameId].frequency));
1720 QApplication::translate(
1722 item->text(0).toStdString().c_str(),
1724 QApplication::UnicodeUTF8));
1738 unsigned int laserFrameId =
searchLaser(item->text(0));
1739 if(laserFrameId == -1)
1743 QString file_name = QFileDialog::getSaveFileName(&
loader_,
1744 tr(
"Save laser sensor"),
1745 QString().fromStdString(
1747 QString(
"/resources/"),
1748 tr(
"Yaml files (*.yaml)"));
1750 std::string file_name_str=file_name.toStdString();
1751 stdr_msgs::LaserSensorMsg lmsg =
new_robot_msg_.laserSensors[laserFrameId];
1760 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1761 msg.setText(QString(ex.what()));
1774 unsigned int sonarFrameId =
searchSonar(item->text(0));
1775 if(sonarFrameId == -1)
1779 QString file_name = QFileDialog::getSaveFileName(&
loader_,
1780 tr(
"Save sonar sensor"),
1781 QString().fromStdString(
1783 QString(
"/resources/"),
1784 tr(
"Resource files (*.yaml *.xml)"));
1786 std::string file_name_str=file_name.toStdString();
1787 stdr_msgs::SonarSensorMsg smsg =
new_robot_msg_.sonarSensors[sonarFrameId];
1796 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1797 msg.setText(QString(ex.what()));
1810 unsigned int frameId =
searchRfid(item->text(0));
1815 QString file_name = QFileDialog::getSaveFileName(&
loader_,
1816 tr(
"Save RFID reader sensor"),
1817 QString().fromStdString(
1819 QString(
"/resources/"),
1820 tr(
"Resource files (*.yaml *.xml)"));
1822 std::string file_name_str=file_name.toStdString();
1823 stdr_msgs::RfidSensorMsg smsg =
new_robot_msg_.rfidSensors[frameId];
1832 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1833 msg.setText(QString(ex.what()));
1849 QString file_name = QFileDialog::getSaveFileName(&
loader_,
1850 tr(
"Save CO2 sensor"),
1851 QString().fromStdString(
1853 QString(
"/resources/"),
1854 tr(
"Resource files (*.yaml *.xml)"));
1856 std::string file_name_str=file_name.toStdString();
1857 stdr_msgs::CO2SensorMsg smsg =
new_robot_msg_.co2Sensors[frameId];
1866 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1867 msg.setText(QString(ex.what()));
1882 QString file_name = QFileDialog::getSaveFileName(&
loader_,
1883 tr(
"Save Thermal sensor"),
1884 QString().fromStdString(
1886 QString(
"/resources/"),
1887 tr(
"Resource files (*.yaml *.xml)"));
1889 std::string file_name_str=file_name.toStdString();
1890 stdr_msgs::ThermalSensorMsg smsg =
new_robot_msg_.thermalSensors[frameId];
1899 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1900 msg.setText(QString(ex.what()));
1915 QString file_name = QFileDialog::getSaveFileName(&
loader_,
1916 tr(
"Save Sound sensor"),
1917 QString().fromStdString(
1919 QString(
"/resources/"),
1920 tr(
"Resource files (*.yaml *.xml)"));
1922 std::string file_name_str=file_name.toStdString();
1923 stdr_msgs::SoundSensorMsg smsg =
new_robot_msg_.soundSensors[frameId];
1932 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1933 msg.setText(QString(ex.what()));
1946 unsigned int laserFrameId =
searchLaser(item->text(0));
1947 if(laserFrameId == -1)
1951 QString file_name = QFileDialog::getOpenFileName(
1953 tr(
"Load laser sensor"),
1954 QString().fromStdString(
1956 QString(
"/resources/"),
1957 tr(
"Resource Files (*.yaml *.xml)"));
1959 if (file_name.isEmpty()) {
1962 std::string old_frame_id = item->text(0).toStdString();
1963 stdr_msgs::LaserSensorMsg lmsg;
1966 stdr_parser::Parser::createMessage<stdr_msgs::LaserSensorMsg>
1967 (file_name.toStdString());
1972 msg.setWindowTitle(QString(
"STDR Parser - Error"));
1973 msg.setText(QString(ex.what()));
1978 lmsg.frame_id = old_frame_id;
1991 unsigned int sonarFrameId =
searchSonar(item->text(0));
1992 if(sonarFrameId == -1)
1996 QString file_name = QFileDialog::getOpenFileName(
1998 tr(
"Load sonar sensor"),
1999 QString().fromStdString(
2001 QString(
"/resources/"),
2002 tr(
"Resource Files (*.yaml *.xml)"));
2004 if (file_name.isEmpty()) {
2007 stdr_msgs::SonarSensorMsg smsg;
2008 std::string old_frame_id = item->text(0).toStdString();
2011 stdr_parser::Parser::createMessage<stdr_msgs::SonarSensorMsg>
2012 (file_name.toStdString());
2017 msg.setWindowTitle(QString(
"STDR Parser - Error"));
2018 msg.setText(QString(ex.what()));
2023 smsg.frame_id = old_frame_id;
2036 unsigned int frameId =
searchRfid(item->text(0));
2041 QString file_name = QFileDialog::getOpenFileName(
2043 tr(
"Load RFID reader sensor"),
2044 QString().fromStdString(
2046 QString(
"/resources/"),
2047 tr(
"Resource Files (*.yaml *.xml)"));
2049 if (file_name.isEmpty()) {
2052 stdr_msgs::RfidSensorMsg smsg;
2053 std::string old_frame_id = item->text(0).toStdString();
2056 stdr_parser::Parser::createMessage<stdr_msgs::RfidSensorMsg>
2057 (file_name.toStdString());
2062 msg.setWindowTitle(QString(
"STDR Parser - Error"));
2063 msg.setText(QString(ex.what()));
2068 smsg.frame_id = old_frame_id;
2083 QString file_name = QFileDialog::getOpenFileName(
2085 tr(
"Load CO2 sensor"),
2086 QString().fromStdString(
2088 QString(
"/resources/"),
2089 tr(
"Resource Files (*.yaml *.xml)"));
2091 if (file_name.isEmpty()) {
2094 stdr_msgs::CO2SensorMsg smsg;
2095 std::string old_frame_id = item->text(0).toStdString();
2098 stdr_parser::Parser::createMessage<stdr_msgs::CO2SensorMsg>
2099 (file_name.toStdString());
2104 msg.setWindowTitle(QString(
"STDR Parser - Error"));
2105 msg.setText(QString(ex.what()));
2110 smsg.frame_id = old_frame_id;
2125 QString file_name = QFileDialog::getOpenFileName(
2127 tr(
"Load thermal sensor"),
2128 QString().fromStdString(
2130 QString(
"/resources/"),
2131 tr(
"Resource Files (*.yaml *.xml)"));
2133 if (file_name.isEmpty()) {
2136 stdr_msgs::ThermalSensorMsg smsg;
2137 std::string old_frame_id = item->text(0).toStdString();
2140 stdr_parser::Parser::createMessage<stdr_msgs::ThermalSensorMsg>
2141 (file_name.toStdString());
2146 msg.setWindowTitle(QString(
"STDR Parser - Error"));
2147 msg.setText(QString(ex.what()));
2152 smsg.frame_id = old_frame_id;
2167 QString file_name = QFileDialog::getOpenFileName(
2169 tr(
"Load sound sensor"),
2170 QString().fromStdString(
2172 QString(
"/resources/"),
2173 tr(
"Resource Files (*.yaml *.xml)"));
2175 if (file_name.isEmpty()) {
2178 stdr_msgs::SoundSensorMsg smsg;
2179 std::string old_frame_id = item->text(0).toStdString();
2182 stdr_parser::Parser::createMessage<stdr_msgs::SoundSensorMsg>
2183 (file_name.toStdString());
2188 msg.setWindowTitle(QString(
"STDR Parser - Error"));
2189 msg.setText(QString(ex.what()));
2194 smsg.frame_id = old_frame_id;
2207 unsigned int sonarFrameId =
searchSonar(item->text(0));
2208 if(sonarFrameId == -1)
2213 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].maxRange));
2216 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].minRange));
2219 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].pose.x));
2222 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].pose.y));
2225 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].coneAngle));
2236 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].pose.theta));
2239 QString().setNum(
new_robot_msg_.sonarSensors[sonarFrameId].frequency));
2242 QApplication::translate(
2244 item->text(0).toStdString().c_str(),
2246 QApplication::UnicodeUTF8));
2260 unsigned int frameId =
searchRfid(item->text(0));
2275 QString().setNum(
new_robot_msg_.rfidSensors[frameId].angleSpan));
2278 QString().setNum(
new_robot_msg_.rfidSensors[frameId].pose.theta));
2281 QString().setNum(
new_robot_msg_.rfidSensors[frameId].signalCutoff));
2284 QString().setNum(
new_robot_msg_.rfidSensors[frameId].frequency));
2287 QApplication::translate(
2288 "RfidAntennaProperties",
2289 item->text(0).toStdString().c_str(),
2291 QApplication::UnicodeUTF8));
2321 QString().setNum(
new_robot_msg_.co2Sensors[frameId].pose.theta));
2330 QApplication::translate(
2331 "CO2SensorProperties",
2332 item->text(0).toStdString().c_str(),
2334 QApplication::UnicodeUTF8));
2352 QString().setNum(
new_robot_msg_.thermalSensors[frameId].maxRange));
2355 QString().setNum(
new_robot_msg_.thermalSensors[frameId].pose.x));
2358 QString().setNum(
new_robot_msg_.thermalSensors[frameId].pose.y));
2361 QString().setNum(
new_robot_msg_.thermalSensors[frameId].angleSpan));
2364 QString().setNum(
new_robot_msg_.thermalSensors[frameId].pose.theta));
2367 QString().setNum(
new_robot_msg_.thermalSensors[frameId].frequency));
2370 QApplication::translate(
2371 "ThermalSensorProperties",
2372 item->text(0).toStdString().c_str(),
2374 QApplication::UnicodeUTF8));
2392 QString().setNum(
new_robot_msg_.soundSensors[frameId].maxRange));
2401 QString().setNum(
new_robot_msg_.soundSensors[frameId].angleSpan));
2404 QString().setNum(
new_robot_msg_.soundSensors[frameId].pose.theta));
2407 QString().setNum(
new_robot_msg_.soundSensors[frameId].frequency));
2410 QApplication::translate(
2411 "SoundSensorProperties",
2412 item->text(0).toStdString().c_str(),
2414 QApplication::UnicodeUTF8));
2428 for(
unsigned int i = 0 ; i <
new_robot_msg_.laserSensors.size() ; i++)
2430 if(
new_robot_msg_.laserSensors[i].frame_id == frameId.toStdString())
2445 for(
unsigned int i = 0 ; i <
new_robot_msg_.sonarSensors.size() ; i++)
2447 if(
new_robot_msg_.sonarSensors[i].frame_id == frameId.toStdString())
2462 for(
unsigned int i = 0 ; i <
new_robot_msg_.rfidSensors.size() ; i++)
2464 if(
new_robot_msg_.rfidSensors[i].frame_id == frameId.toStdString())
2478 for(
unsigned int i = 0 ; i <
new_robot_msg_.co2Sensors.size() ; i++)
2480 if(
new_robot_msg_.co2Sensors[i].frame_id == frameId.toStdString())
2494 for(
unsigned int i = 0 ; i <
new_robot_msg_.thermalSensors.size() ; i++)
2496 if(
new_robot_msg_.thermalSensors[i].frame_id == frameId.toStdString())
2510 for(
unsigned int i = 0 ; i <
new_robot_msg_.soundSensors.size() ; i++)
2512 if(
new_robot_msg_.soundSensors[i].frame_id == frameId.toStdString())
2542 for(
int i = count - 1 ; i >= 0 ; i--)
2547 for(
unsigned int i = 0 ; i <
new_robot_msg_.laserSensors.size() ; i++)
2553 for(
int i = count - 1 ; i >= 0 ; i--)
2558 for(
unsigned int i = 0 ; i <
new_robot_msg_.rfidSensors.size() ; i++)
2564 for(
int i = count - 1 ; i >= 0 ; i--)
2569 for(
unsigned int i = 0 ; i <
new_robot_msg_.thermalSensors.size() ; i++)
2575 for(
int i = count - 1 ; i >= 0 ; i--)
2580 for(
unsigned int i = 0 ; i <
new_robot_msg_.soundSensors.size() ; i++)
2586 for(
int i = count - 1 ; i >= 0 ; i--)
2591 for(
unsigned int i = 0 ; i <
new_robot_msg_.sonarSensors.size() ; i++)
2596 for(
unsigned int i = 0 ; i <
new_robot_msg_.footprint.points.size() ; i++)
2609 QTreeWidgetItem *item,
2610 stdr_msgs::LaserSensorMsg l)
2612 for(
unsigned int i = 0 ; i < item->childCount() ; i++)
2614 if(item->child(i)->text(0) == QString(
"Angle span"))
2616 item->child(i)->setText(1,QString().setNum(l.maxAngle - l.minAngle));
2618 else if(item->child(i)->text(0) == QString(
"Orientation"))
2620 item->child(i)->setText(1,QString().setNum(l.pose.theta));
2622 else if(item->child(i)->text(0) == QString(
"Max range"))
2624 item->child(i)->setText(1,QString().setNum(l.maxRange));
2626 else if(item->child(i)->text(0) == QString(
"Number of rays"))
2628 item->child(i)->setText(1,QString().setNum(l.numRays));
2630 else if(item->child(i)->text(0) == QString(
"Min range"))
2632 item->child(i)->setText(1,QString().setNum(l.minRange));
2634 else if(item->child(i)->text(0) == QString(
"Noise mean"))
2636 item->child(i)->setText(1,QString().setNum(l.noise.noiseMean));
2638 else if(item->child(i)->text(0) == QString(
"Noise std"))
2640 item->child(i)->setText(1,QString().setNum(l.noise.noiseStd));
2642 else if(item->child(i)->text(0) == QString(
"Pose - x"))
2644 item->child(i)->setText(1,QString().setNum(l.pose.x));
2646 else if(item->child(i)->text(0) == QString(
"Pose - y"))
2648 item->child(i)->setText(1,QString().setNum(l.pose.y));
2650 else if(item->child(i)->text(0) == QString(
"Frequency"))
2652 item->child(i)->setText(1,QString().setNum(l.frequency));
2664 if(laserFrameId == -1)
2668 float max_range = 1000.0;
2669 float min_range = 0.0;
2679 text().toFloat() / 2.0;
2680 if( angleSpan <= 0 )
2682 showMessage(QString(
"Laser angle span invalid :") +
2683 QString().setNum(angleSpan * 2.0));
2686 new_robot_msg_.laserSensors[laserFrameId].minAngle = - angleSpan;
2691 else if(
current_laser_->child(i)->text(0) == QString(
"Orientation"))
2696 1,QString().setNum(orientation));
2699 new_robot_msg_.laserSensors[laserFrameId].pose.theta = orientation;
2703 else if(
current_laser_->child(i)->text(0) == QString(
"Max range"))
2707 if( max_range <= 0 )
2709 showMessage(QString(
"Laser maximum range invalid :") +
2710 QString().setNum(max_range));
2713 if( max_range < min_range )
2715 showMessage(QString(
"Laser maximum range lower than minimum range"));
2718 current_laser_->child(i)->setText(1,QString().setNum(max_range));
2723 else if(
current_laser_->child(i)->text(0) == QString(
"Number of rays"))
2728 showMessage(QString(
"Laser rays number invalid :") +
2729 QString().setNum(rays));
2737 else if(
current_laser_->child(i)->text(0) == QString(
"Min range"))
2743 showMessage(QString(
"Laser minimum range invalid :") +
2744 QString().setNum(min_range));
2747 if( min_range > max_range )
2749 showMessage(QString(
"Laser minimum range higher than maximum range"));
2752 current_laser_->child(i)->setText(1,QString().setNum(min_range));
2757 else if(
current_laser_->child(i)->text(0) == QString(
"Noise mean"))
2761 current_laser_->child(i)->setText(1,QString().setNum(noiseMean));
2767 else if(
current_laser_->child(i)->text(0) == QString(
"Noise std"))
2773 showMessage(QString(
"Laser standard deviation of noise invalid :") +
2774 QString().setNum(noiseStd));
2783 else if(
current_laser_->child(i)->text(0) == QString(
"Pose - x"))
2792 else if(
current_laser_->child(i)->text(0) == QString(
"Pose - y"))
2801 else if(
current_laser_->child(i)->text(0) == QString(
"Frequency"))
2805 if( frequency <= 0 )
2807 showMessage(QString(
"Laser publishing frequency invalid :") +
2808 QString().setNum(frequency));
2811 current_laser_->child(i)->setText(1,QString().setNum(frequency));
2828 if(laserFrameId == -1)
2832 float max_range = 1000.0;
2833 float min_range = 0.0;
2843 text().toFloat() / 2.0;
2844 if( angleSpan <= 0 )
2846 showMessage(QString(
"Laser angle span invalid :") +
2847 QString().setNum(angleSpan * 2.0));
2850 new_robot_msg_.laserSensors[laserFrameId].minAngle = - angleSpan;
2855 else if(
current_laser_->child(i)->text(0) == QString(
"Orientation"))
2860 1,QString().setNum(orientation));
2863 new_robot_msg_.laserSensors[laserFrameId].pose.theta = orientation;
2867 else if(
current_laser_->child(i)->text(0) == QString(
"Max range"))
2871 if( max_range <= 0 )
2873 showMessage(QString(
"Laser maximum range invalid :") +
2874 QString().setNum(max_range));
2877 if( max_range < min_range )
2879 showMessage(QString(
"Laser maximum range lower than minimum range"));
2882 current_laser_->child(i)->setText(1,QString().setNum(max_range));
2887 else if(
current_laser_->child(i)->text(0) == QString(
"Number of rays"))
2892 showMessage(QString(
"Laser rays number invalid :") +
2893 QString().setNum(rays));
2901 else if(
current_laser_->child(i)->text(0) == QString(
"Min range"))
2907 showMessage(QString(
"Laser minimum range invalid :") +
2908 QString().setNum(min_range));
2911 if( min_range > max_range )
2913 showMessage(QString(
"Laser minimum range higher than maximum range"));
2916 current_laser_->child(i)->setText(1,QString().setNum(min_range));
2921 else if(
current_laser_->child(i)->text(0) == QString(
"Noise mean"))
2925 current_laser_->child(i)->setText(1,QString().setNum(noiseMean));
2931 else if(
current_laser_->child(i)->text(0) == QString(
"Noise std"))
2937 showMessage(QString(
"Laser standard deviation of noise invalid :") +
2938 QString().setNum(noiseStd));
2947 else if(
current_laser_->child(i)->text(0) == QString(
"Pose - x"))
2956 else if(
current_laser_->child(i)->text(0) == QString(
"Pose - y"))
2965 else if(
current_laser_->child(i)->text(0) == QString(
"Frequency"))
2969 if( frequency <= 0 )
2971 showMessage(QString(
"Laser publishing frequency invalid :") +
2972 QString().setNum(frequency));
2975 current_laser_->child(i)->setText(1,QString().setNum(frequency));
2995 float min_range = 0;
2996 float max_range = 10000.0;
3004 if( cone_span <= 0 )
3006 showMessage(QString(
"Sonar cone span invalid :") +
3007 QString().setNum(cone_span));
3010 current_sonar_->child(i)->setText(1,QString().setNum(cone_span));
3015 else if(
current_sonar_->child(i)->text(0) == QString(
"Orientation"))
3020 setText(1,QString().setNum(orientation));
3025 else if(
current_sonar_->child(i)->text(0) == QString(
"Max range"))
3028 if( max_range <= 0 )
3030 showMessage(QString(
"Sonar maximum range invalid :") +
3031 QString().setNum(max_range));
3034 if( max_range < min_range )
3036 showMessage(QString(
"Sonar maximum range lower than minimum range."));
3040 setText(1,QString().setNum(max_range));
3045 else if(
current_sonar_->child(i)->text(0) == QString(
"Min range"))
3050 showMessage(QString(
"Sonar minimum range invalid :") +
3051 QString().setNum(min_range));
3054 if( max_range < min_range )
3057 QString(
"Sonar minimum range higher than maximum range."));
3060 current_sonar_->child(i)->setText(1,QString().setNum(min_range));
3065 else if(
current_sonar_->child(i)->text(0) == QString(
"Noise mean"))
3070 setText(1,QString().setNum(noiseMean));
3071 new_robot_msg_.sonarSensors[frameId].noise.noiseMean = noiseMean;
3075 else if(
current_sonar_->child(i)->text(0) == QString(
"Noise std"))
3081 showMessage(QString(
"Sonar noise standard deviation invalid :") +
3082 QString().setNum(noiseStd));
3086 child(i)->setText(1,QString().setNum(noiseStd));
3091 else if(
current_sonar_->child(i)->text(0) == QString(
"Pose - x"))
3099 else if(
current_sonar_->child(i)->text(0) == QString(
"Pose - y"))
3107 else if(
current_sonar_->child(i)->text(0) == QString(
"Frequency"))
3111 if( frequency <= 0 )
3113 showMessage(QString(
"Sonar publishing frequency invalid :") +
3114 QString().setNum(frequency));
3117 current_sonar_->child(i)->setText(1,QString().setNum(frequency));
3138 float min_range = 0;
3139 float max_range = 10000.0;
3147 if( cone_span <= 0 )
3149 showMessage(QString(
"Sonar cone span invalid :") +
3150 QString().setNum(cone_span));
3153 current_sonar_->child(i)->setText(1,QString().setNum(cone_span));
3158 else if(
current_sonar_->child(i)->text(0) == QString(
"Orientation"))
3163 setText(1,QString().setNum(orientation));
3168 else if(
current_sonar_->child(i)->text(0) == QString(
"Max range"))
3171 if( max_range <= 0 )
3173 showMessage(QString(
"Sonar maximum range invalid :") +
3174 QString().setNum(max_range));
3177 if( max_range < min_range )
3179 showMessage(QString(
"Sonar maximum range lower than minimum range."));
3183 setText(1,QString().setNum(max_range));
3188 else if(
current_sonar_->child(i)->text(0) == QString(
"Min range"))
3193 showMessage(QString(
"Sonar minimum range invalid :") +
3194 QString().setNum(min_range));
3197 if( max_range < min_range )
3200 QString(
"Sonar minimum range higher than maximum range."));
3203 current_sonar_->child(i)->setText(1,QString().setNum(min_range));
3208 else if(
current_sonar_->child(i)->text(0) == QString(
"Noise mean"))
3213 setText(1,QString().setNum(noiseMean));
3214 new_robot_msg_.sonarSensors[frameId].noise.noiseMean = noiseMean;
3218 else if(
current_sonar_->child(i)->text(0) == QString(
"Noise std"))
3224 showMessage(QString(
"Sonar noise standard deviation invalid :") +
3225 QString().setNum(noiseStd));
3229 child(i)->setText(1,QString().setNum(noiseStd));
3234 else if(
current_sonar_->child(i)->text(0) == QString(
"Pose - x"))
3242 else if(
current_sonar_->child(i)->text(0) == QString(
"Pose - y"))
3250 else if(
current_sonar_->child(i)->text(0) == QString(
"Frequency"))
3254 if( frequency <= 0 )
3256 showMessage(QString(
"Sonar publishing frequency invalid :") +
3257 QString().setNum(frequency));
3260 current_sonar_->child(i)->setText(1,QString().setNum(frequency));
3276 QTreeWidgetItem *item,
3277 stdr_msgs::SonarSensorMsg l)
3284 for(
unsigned int i = 0 ; i < item->childCount() ; i++)
3286 if(item->child(i)->text(0) == QString(
"Cone span"))
3288 item->child(i)->setText(1,QString().setNum(l.coneAngle));
3290 else if(item->child(i)->text(0) == QString(
"Orientation"))
3292 item->child(i)->setText(1,QString().setNum(l.pose.theta));
3294 else if(item->child(i)->text(0) == QString(
"Max range"))
3296 item->child(i)->setText(1,QString().setNum(l.maxRange));
3298 else if(item->child(i)->text(0) == QString(
"Min range"))
3300 item->child(i)->setText(1,QString().setNum(l.minRange));
3302 else if(item->child(i)->text(0) == QString(
"Noise mean"))
3304 item->child(i)->setText(1,QString().setNum(l.noise.noiseMean));
3306 else if(item->child(i)->text(0) == QString(
"Noise std"))
3308 item->child(i)->setText(1,QString().setNum(l.noise.noiseStd));
3310 else if(item->child(i)->text(0) == QString(
"Pose - x"))
3312 item->child(i)->setText(1,QString().setNum(l.pose.x));
3314 else if(item->child(i)->text(0) == QString(
"Pose - y"))
3316 item->child(i)->setText(1,QString().setNum(l.pose.y));
3318 else if(item->child(i)->text(0) == QString(
"Frequency"))
3320 item->child(i)->setText(1,QString().setNum(l.frequency));
3332 QTreeWidgetItem *item,
3333 stdr_msgs::RfidSensorMsg l)
3335 unsigned int frameId=
searchRfid(item->text(0));
3340 for(
unsigned int i = 0 ; i < item->childCount() ; i++)
3342 if(item->child(i)->text(0) == QString(
"Angle span"))
3344 item->child(i)->setText(1,QString().setNum(l.angleSpan));
3346 else if(item->child(i)->text(0) == QString(
"Orientation"))
3348 item->child(i)->setText(1,QString().setNum(l.pose.theta));
3350 else if(item->child(i)->text(0) == QString(
"Max range"))
3352 item->child(i)->setText(1,QString().setNum(l.maxRange));
3354 else if(item->child(i)->text(0) == QString(
"Signal cutoff"))
3356 item->child(i)->setText(1,QString().setNum(l.signalCutoff));
3358 else if(item->child(i)->text(0) == QString(
"Pose - x"))
3360 item->child(i)->setText(1,QString().setNum(l.pose.x));
3362 else if(item->child(i)->text(0) == QString(
"Pose - y"))
3364 item->child(i)->setText(1,QString().setNum(l.pose.y));
3366 else if(item->child(i)->text(0) == QString(
"Frequency"))
3368 item->child(i)->setText(1,QString().setNum(l.frequency));
3376 QTreeWidgetItem *item,
3377 stdr_msgs::CO2SensorMsg l)
3384 for(
unsigned int i = 0 ; i < item->childCount() ; i++)
3390 if(item->child(i)->text(0) == QString(
"Orientation"))
3392 item->child(i)->setText(1,QString().setNum(l.pose.theta));
3394 else if(item->child(i)->text(0) == QString(
"Max range"))
3396 item->child(i)->setText(1,QString().setNum(l.maxRange));
3402 else if(item->child(i)->text(0) == QString(
"Pose - x"))
3404 item->child(i)->setText(1,QString().setNum(l.pose.x));
3406 else if(item->child(i)->text(0) == QString(
"Pose - y"))
3408 item->child(i)->setText(1,QString().setNum(l.pose.y));
3410 else if(item->child(i)->text(0) == QString(
"Frequency"))
3412 item->child(i)->setText(1,QString().setNum(l.frequency));
3420 QTreeWidgetItem *item,
3421 stdr_msgs::ThermalSensorMsg l)
3428 for(
unsigned int i = 0 ; i < item->childCount() ; i++)
3430 if(item->child(i)->text(0) == QString(
"Angle span"))
3432 item->child(i)->setText(1,QString().setNum(l.angleSpan));
3434 else if(item->child(i)->text(0) == QString(
"Orientation"))
3436 item->child(i)->setText(1,QString().setNum(l.pose.theta));
3438 else if(item->child(i)->text(0) == QString(
"Max range"))
3440 item->child(i)->setText(1,QString().setNum(l.maxRange));
3446 else if(item->child(i)->text(0) == QString(
"Pose - x"))
3448 item->child(i)->setText(1,QString().setNum(l.pose.x));
3450 else if(item->child(i)->text(0) == QString(
"Pose - y"))
3452 item->child(i)->setText(1,QString().setNum(l.pose.y));
3454 else if(item->child(i)->text(0) == QString(
"Frequency"))
3456 item->child(i)->setText(1,QString().setNum(l.frequency));
3464 QTreeWidgetItem *item,
3465 stdr_msgs::SoundSensorMsg l)
3472 for(
unsigned int i = 0 ; i < item->childCount() ; i++)
3474 if(item->child(i)->text(0) == QString(
"Angle span"))
3476 item->child(i)->setText(1,QString().setNum(l.angleSpan));
3478 else if(item->child(i)->text(0) == QString(
"Orientation"))
3480 item->child(i)->setText(1,QString().setNum(l.pose.theta));
3482 else if(item->child(i)->text(0) == QString(
"Max range"))
3484 item->child(i)->setText(1,QString().setNum(l.maxRange));
3490 else if(item->child(i)->text(0) == QString(
"Pose - x"))
3492 item->child(i)->setText(1,QString().setNum(l.pose.x));
3494 else if(item->child(i)->text(0) == QString(
"Pose - y"))
3496 item->child(i)->setText(1,QString().setNum(l.pose.y));
3498 else if(item->child(i)->text(0) == QString(
"Frequency"))
3500 item->child(i)->setText(1,QString().setNum(l.frequency));
3516 for(
unsigned int i = 0 ; i <
current_rfid_->childCount() ; i++)
3520 if(
current_rfid_->child(i)->text(0) == QString(
"Angle span"))
3524 if( angle_span <= 0 )
3526 showMessage(QString(
"Rfid antenna angle span invalid :") +
3527 QString().setNum(angle_span));
3530 current_rfid_->child(i)->setText(1,QString().setNum(angle_span));
3535 else if(
current_rfid_->child(i)->text(0) == QString(
"Orientation"))
3541 setText(1,QString().setNum(orientation));
3546 else if(
current_rfid_->child(i)->text(0) == QString(
"Max range"))
3553 showMessage(QString(
"Rfid antenna maximum range invalid :") +
3554 QString().setNum(maxRange));
3557 current_rfid_->child(i)->setText(1,QString().setNum(maxRange));
3562 else if(
current_rfid_->child(i)->text(0) == QString(
"Pose - x"))
3570 else if(
current_rfid_->child(i)->text(0) == QString(
"Pose - y"))
3578 else if(
current_rfid_->child(i)->text(0) == QString(
"Signal cutoff"))
3583 current_rfid_->child(i)->setText(1,QString().setNum(signal));
3588 else if(
current_rfid_->child(i)->text(0) == QString(
"Frequency"))
3593 if( frequency <= 0 )
3595 showMessage(QString(
"Rfid antenna publishing frequency invalid :") +
3596 QString().setNum(frequency));
3599 current_rfid_->child(i)->setText(1,QString().setNum(frequency));
3643 setText(1,QString().setNum(orientation));
3655 showMessage(QString(
"CO2 sensor maximum range invalid :") +
3656 QString().setNum(maxRange));
3685 if( frequency <= 0 )
3687 showMessage(QString(
"CO2 sensor publishing frequency invalid :") +
3688 QString().setNum(frequency));
3718 if( angle_span <= 0 )
3720 showMessage(QString(
"Thermal sensor angle span invalid :") +
3721 QString().setNum(angle_span));
3735 setText(1,QString().setNum(orientation));
3747 showMessage(QString(
"Thermal sensor maximum range invalid :") +
3748 QString().setNum(maxRange));
3777 if( frequency <= 0 )
3779 showMessage(QString(
"Thermal sensor publishing frequency invalid :") +
3780 QString().setNum(frequency));
3810 if( angle_span <= 0 )
3812 showMessage(QString(
"Sound sensor angle span invalid :") +
3813 QString().setNum(angle_span));
3827 setText(1,QString().setNum(orientation));
3839 showMessage(QString(
"Sound sensor maximum range invalid :") +
3840 QString().setNum(maxRange));
3869 if( frequency <= 0 )
3871 showMessage(QString(
"Sound sensor publishing frequency invalid :") +
3872 QString().setNum(frequency));
3896 for(
unsigned int i = 0 ; i <
current_rfid_->childCount() ; i++)
3900 if(
current_rfid_->child(i)->text(0) == QString(
"Angle span"))
3904 if( angle_span <= 0 )
3906 showMessage(QString(
"Rfid antenna angle span invalid :") +
3907 QString().setNum(angle_span));
3910 current_rfid_->child(i)->setText(1,QString().setNum(angle_span));
3915 else if(
current_rfid_->child(i)->text(0) == QString(
"Orientation"))
3921 setText(1,QString().setNum(orientation));
3926 else if(
current_rfid_->child(i)->text(0) == QString(
"Max range"))
3933 showMessage(QString(
"Rfid antenna maximum range invalid :") +
3934 QString().setNum(maxRange));
3937 current_rfid_->child(i)->setText(1,QString().setNum(maxRange));
3942 else if(
current_rfid_->child(i)->text(0) == QString(
"Pose - x"))
3950 else if(
current_rfid_->child(i)->text(0) == QString(
"Pose - y"))
3958 else if(
current_rfid_->child(i)->text(0) == QString(
"Signal cutoff"))
3963 current_rfid_->child(i)->setText(1,QString().setNum(signal));
3968 else if(
current_rfid_->child(i)->text(0) == QString(
"Frequency"))
3973 if( frequency <= 0 )
3975 showMessage(QString(
"Rfid antenna publishing frequency invalid :") +
3976 QString().setNum(frequency));
3979 current_rfid_->child(i)->setText(1,QString().setNum(frequency));
4021 setText(1,QString().setNum(orientation));
4033 showMessage(QString(
"CO2 source maximum range invalid :") +
4034 QString().setNum(maxRange));
4063 if( frequency <= 0 )
4065 showMessage(QString(
"CO2 sensor publishing frequency invalid :") +
4066 QString().setNum(frequency));
4094 if( angle_span <= 0 )
4096 showMessage(QString(
"Thermal sensor angle span invalid :") +
4097 QString().setNum(angle_span));
4111 setText(1,QString().setNum(orientation));
4123 showMessage(QString(
"Thermal sensor maximum range invalid :") +
4124 QString().setNum(maxRange));
4153 if( frequency <= 0 )
4155 showMessage(QString(
"Thermal sensor publishing frequency invalid :") +
4156 QString().setNum(frequency));
4184 if( angle_span <= 0 )
4186 showMessage(QString(
"Sound sensor angle span invalid :") +
4187 QString().setNum(angle_span));
4201 setText(1,QString().setNum(orientation));
4213 showMessage(QString(
"Sound sensor maximum range invalid :") +
4214 QString().setNum(maxRange));
4243 if( frequency <= 0 )
4245 showMessage(QString(
"Sound sensor publishing frequency invalid :") +
4246 QString().setNum(frequency));
4333 int count = item->childCount();
4334 for(
int i = count - 1 ; i >= 0 ; i--)
4355 for(
unsigned int i = 0 ; i <
new_robot_msg_.footprint.points.size() ; i++)
4366 for(
unsigned int i = 0 ; i <
new_robot_msg_.laserSensors.size() ; i++)
4393 for(
unsigned int i = 0 ; i <
new_robot_msg_.sonarSensors.size() ; i++)
4420 for(
unsigned int i = 0 ; i <
new_robot_msg_.rfidSensors.size() ; i++)
4447 for(
unsigned int i = 0 ; i <
new_robot_msg_.co2Sensors.size() ; i++)
4474 for(
unsigned int i = 0 ; i <
new_robot_msg_.thermalSensors.size() ; i++)
4501 for(
unsigned int i = 0 ; i <
new_robot_msg_.soundSensors.size() ; i++)
4538 loader_.robotTreeWidget->resizeColumnToContents(0);
4539 loader_.robotTreeWidget->resizeColumnToContents(1);
4540 loader_.robotTreeWidget->resizeColumnToContents(2);
4541 loader_.robotTreeWidget->resizeColumnToContents(3);
4542 loader_.robotTreeWidget->resizeColumnToContents(4);
4552 painter.setPen(Qt::blue);
4556 painter.drawEllipse(
4562 painter.setPen(Qt::red);
4574 QPointF *points =
new QPointF[
new_robot_msg_.footprint.points.size() + 1];
4578 for(
unsigned int i = 0 ;
4586 if( pow(x,2) + pow(y,2) > max_val )
4588 max_val = pow(x,2) + pow(y,2);
4591 points[i] = QPointF(
4604 painter.drawPolyline(points,
new_robot_msg_.footprint.points.size() + 1);
4606 painter.setPen(Qt::red);
4608 max_val = sqrt(max_val);
4613 250 + max_val *
climax_ * 1.05 * cos(
4615 250 - max_val *
climax_ * 1.05 * sin(
4619 loader_.robotPreviewLabel->setPixmap(
4630 QBrush brush(QColor(0,200,0,50));
4631 painter.setBrush(brush);
4632 float robotOrientation =
4635 for(
unsigned int i = 0 ; i <
new_robot_msg_.laserSensors.size() ; i++)
4639 brush = QBrush(QColor(0,200,0,150));
4643 brush = QBrush(QColor(0,200,0,50));
4645 painter.setBrush(brush);
4649 float newx = laserx * cos(robotOrientation) -
4650 lasery * sin(robotOrientation);
4651 float newy = laserx * sin(robotOrientation) +
4652 lasery * cos(robotOrientation);
4671 loader_.robotPreviewLabel->setPixmap(
4682 QBrush brush(QColor(200,0,0,50));
4683 painter.setBrush(brush);
4684 float robotOrientation =
4687 for(
unsigned int i = 0 ; i <
new_robot_msg_.sonarSensors.size() ; i++)
4692 brush = QBrush(QColor(200,0,0,150));
4696 brush = QBrush(QColor(200,0,0,50));
4698 painter.setBrush(brush);
4702 float newx = sonarx * cos(robotOrientation) -
4703 sonary * sin(robotOrientation);
4704 float newy = sonarx * sin(robotOrientation) +
4705 sonary * cos(robotOrientation);
4719 loader_.robotPreviewLabel->setPixmap(
4730 QBrush brush(QColor(0,0,200,20));
4731 painter.setBrush(brush);
4732 float robotOrientation =
4735 for(
unsigned int i = 0 ; i <
new_robot_msg_.rfidSensors.size() ; i++)
4740 brush = QBrush(QColor(0,0,200,30));
4744 brush = QBrush(QColor(0,0,200,10));
4750 rfidx * cos(robotOrientation) - rfidy * sin(robotOrientation);
4752 rfidx * sin(robotOrientation) + rfidy * cos(robotOrientation);
4756 250 -
new_robot_msg_.rfidSensors[i].maxRange * climax_ - newy * climax_,
4764 loader_.robotPreviewLabel->setPixmap(
4773 QBrush brush(QColor(100,0,200,20));
4774 painter.setBrush(brush);
4775 float robotOrientation =
4778 for(
unsigned int i = 0 ; i <
new_robot_msg_.co2Sensors.size() ; i++)
4783 brush = QBrush(QColor(100,0,200,30));
4787 brush = QBrush(QColor(100,0,200,10));
4793 x * cos(robotOrientation) - y * sin(robotOrientation);
4795 x * sin(robotOrientation) + y * cos(robotOrientation);
4799 250 -
new_robot_msg_.co2Sensors[i].maxRange * climax_ - newy * climax_,
4805 loader_.robotPreviewLabel->setPixmap(
4815 QBrush brush(QColor(200,0,0,10));
4816 painter.setBrush(brush);
4817 float robotOrientation =
4820 for(
unsigned int i = 0 ; i <
new_robot_msg_.thermalSensors.size() ; i++)
4825 brush = QBrush(QColor(200,0,0,30));
4829 brush = QBrush(QColor(200,0,0,10));
4835 x * cos(robotOrientation) - y * sin(robotOrientation);
4837 x * sin(robotOrientation) + y * cos(robotOrientation);
4841 250 -
new_robot_msg_.thermalSensors[i].maxRange * climax_ - newy * climax_,
4849 loader_.robotPreviewLabel->setPixmap(
4859 QBrush brush(QColor(0,50,200,20));
4860 painter.setBrush(brush);
4861 float robotOrientation =
4864 for(
unsigned int i = 0 ; i <
new_robot_msg_.soundSensors.size() ; i++)
4869 brush = QBrush(QColor(0,50,200,30));
4873 brush = QBrush(QColor(0,50,200,10));
4879 x * cos(robotOrientation) - y * sin(robotOrientation);
4881 x * sin(robotOrientation) + y * cos(robotOrientation);
4885 250 -
new_robot_msg_.soundSensors[i].maxRange * climax_ - newy * climax_,
4893 loader_.robotPreviewLabel->setPixmap(
4903 QString file_name = QFileDialog::getSaveFileName(&
loader_,
4905 QString().fromStdString(
4907 QString(
"/resources/"),
4908 tr(
"Resource files (*.yaml *.xml)"));
4920 QString file_name = QFileDialog::getOpenFileName(
4923 QString().fromStdString(
4925 QString(
"/resources/"),
4926 tr(
"Resource Files (*.yaml *.xml)"));
4929 if (file_name.isEmpty()) {
4935 stdr_parser::Parser::createMessage<stdr_msgs::RobotMsg>
4936 (file_name.toStdString());
4941 msg.setWindowTitle(QString(
"STDR Parser - Error"));
4942 msg.setText(QString(ex.what()));
4949 CRobotCreatorConnector::laser_number = -1;
4950 CRobotCreatorConnector::sonar_number = -1;
4951 CRobotCreatorConnector::rfid_number = -1;
4952 CRobotCreatorConnector::co2_sensors_number = -1;
4953 CRobotCreatorConnector::thermal_sensors_number = -1;
4954 CRobotCreatorConnector::sound_sensors_number = -1;
5015 msgBox.setText(msg);
void updateRfidAntenna(void)
Called when the update button of the properties widget is clicked.
void updateLaserTree(QTreeWidgetItem *item, stdr_msgs::LaserSensorMsg l)
Updates a tree item with a specific laser sensor.
void eraseCO2Sensor(QTreeWidgetItem *item)
Erases a specific co2 sensor based on a tree item.
void eraseRfid(QTreeWidgetItem *item)
Erases a specific rfid antenna sensor based on a tree item.
QTreeWidgetItem * current_laser_
Tree item of the currently clicked sonar.
QTreeWidgetItem robotInfoFootprint
Holds the tree items that contain the footprint points.
void saveRfidAntenna(QTreeWidgetItem *item)
Saves a specific rfid reader sensor in a file.
QTreeWidgetItem * current_sonar_
Tree item of the currently clicked rfid.
CRobotPropertiesLoader robotPropLoader
Object of robot footprint widget.
void showMessage(QString msg)
Pops up a message box with a specific message.
CKinematicPropertiesLoader kinematicPropLoader
Object of rfid antenna properties widget.
int searchRfid(QString frameId)
Returns the ID of an rfid antenna sensor.
QTreeWidgetItem sonarsNode
Tree item for the rfid antennas root.
void drawRobot(void)
Draws a robot.
void saveThermalSensor(QTreeWidgetItem *item)
Saves a specific thermal sensor in a file.
void drawCO2Sensors(void)
Draws the robot's rfid antennas.
~CRobotCreatorConnector(void)
Default destructor.
QTreeWidgetItem * current_rfid_
void drawLasers(void)
Draws the robot's lasers.
void loadLaser(QTreeWidgetItem *item)
Loads a specific laser sensor from a file.
void updateSoundSensorTree(QTreeWidgetItem *item, stdr_msgs::SoundSensorMsg l)
Updates a tree item with a specific sound sensor.
CRobotCreatorLoader loader_
Container of the new robot message.
void initialise(void)
Initializes the robot creator.
void addFootprintPoint(void)
Adds a footprint point in the new robot.
int searchSoundSensor(QString frameId)
Returns the ID of a sound sensor.
CRfidAntennaPropertiesLoader rfidAntennaPropLoader
void addSoundSensor(void)
Adds a sound sensor in the new robot.
void drawThermalSensors(void)
Draws the robot's rfid antennas.
QTreeWidgetItem robotInfoOrientation
Tree item for the robot radius.
void loadSoundSensor(QTreeWidgetItem *item)
Loads a specific sound sensor from a file.
void updateLaserOpen(void)
Called when the refresh button of the properties widget is clicked.
void saveSonar(QTreeWidgetItem *item)
Saves a specific sonar sensor in a file.
static int sound_sensors_number
void updateThermalSensorTree(QTreeWidgetItem *item, stdr_msgs::ThermalSensorMsg l)
Updates a tree item with a specific thermal sensor.
CLaserPropertiesLoader laserPropLoader
Object of sonar properties widget.
void updateThermalSensor(void)
Called when the update button of the properties widget is clicked.
void eraseSoundSensor(QTreeWidgetItem *item)
Erases a specific sound sensor based on a tree item.
void loadRobotPressed(stdr_msgs::RobotMsg newRobotMsg)
Emitted when the "load robot in map" button is pressed.
unsigned int thermal_sensor_hightlight_id_
QTreeWidgetItem kinematicNode
Tree item for the robot orientation.
void updateRobotTree(void)
Updates the robot's tree widget.
CRobotFootprintLoader robotFootLoader
Object of laser properties widget.
void addLaser(void)
Adds a laser sensor in the new robot.
void updateSonar(void)
Called when the update button of the properties widget is clicked.
static int thermal_sensors_number
void addSonar(void)
Adds a sonar sensor in the new robot.
TFSIMD_FORCE_INLINE const tfScalar & y() const
unsigned int sound_sensor_hightlight_id_
Tree item of the currently clicked laser.
void updateKinematicModel(void)
Called when the update button of the kinematic model widget is clicked.
void saveSoundSensor(QTreeWidgetItem *item)
Saves a specific sound sensor in a file.
void getRobotFromYaml(void)
Called when the load robot button.
void saveRobot(void)
Called when the save robot button is clicked.
void editThermalSensor(QTreeWidgetItem *item)
Edits a specific thermal sensor based on a tree item. \ Initiates the thermal sensor editor widget...
void updateSoundSensor(void)
Called when the update button of the properties widget is clicked.
void updateFootprintPoint(void)
Called when the update button of the footprint widget is clicked.
CSoundSensorPropertiesLoader soundSensorPropLoader
void updateRfidTree(QTreeWidgetItem *item, stdr_msgs::RfidSensorMsg l)
Updates a tree item with a specific rfid reader sensor.
void updateRobot(void)
Called when the update button of the properties widget is clicked.
void editCO2Sensor(QTreeWidgetItem *item)
Edits a specific co2 sensor based on a tree item. \ Initiates the co2 sensor editor widget...
QTreeWidgetItem robotNode
Tree item for the lasers root.
void deleteTreeNode(QTreeWidgetItem *item)
Deletes a specific tree item and it's children recursively.
void updateSonarTree(QTreeWidgetItem *item, stdr_msgs::SonarSensorMsg l)
Updates a tree item with a specific sonar sensor.
QTreeWidgetItem * current_sound_sensor_
Tree item of the currently clicked footprint point.
void editSonar(QTreeWidgetItem *item)
Edits a specific sonar sensor based on a tree item. Initiates the sonar sensor editor widget...
QTreeWidgetItem soundSensorsNode
Tree item for the kinematic.
QTreeWidgetItem co2SensorsNode
static void saveMessage(T msg, std::string file_name)
QTreeWidgetItem * current_thermal_sensor_
CSonarPropertiesLoader sonarPropLoader
Object of robot kinematic properties widget.
void updateRobotPreview(void)
Updates the robot's preview.
void editFootprintPoint(QTreeWidgetItem *item)
Edits a specific footprint point based on a tree item. Initiates the footprint editor widget...
stdr_msgs::RobotMsg getNewRobot(void)
Returns the created robot.
int searchLaser(QString frameId)
Returns the ID of a laser sensor.
void updateSoundSensorOpen(void)
Called when the refresh button of the properties widget is clicked.
void loadRobot(void)
Called when the load robot in map button is clicked.
void updateLaser(void)
Called when the update button of the properties widget is clicked.
QTreeWidgetItem rfidAntennasNode
QTreeWidgetItem robotInfoRadius
Tree item for the robot footprint.
QTreeWidgetItem lasersNode
Tree item for the sonars root.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void updateFootprintPointOpen(void)
Called when the refresh button of the properties widget is clicked.
void addThermalSensor(void)
Adds a thermal sensor in the new robot.
float climax_
Object of CRobotCreatorLoader.
void saveLaser(QTreeWidgetItem *item)
Saves a specific laser sensor in a file.
int searchCO2Sensor(QString frameId)
Returns the ID of an co2 sensor.
void saveCO2Sensor(QTreeWidgetItem *item)
Saves a specific co2 sensor in a file.
int searchSonar(QString frameId)
Returns the ID of a sonar sensor.
unsigned int sonar_hightlight_id_
Current rfid antenna for highlight.
void loadRfidAntenna(QTreeWidgetItem *item)
Loads a specific rfid reader sensor from a file.
int searchThermalSensor(QString frameId)
Returns the ID of a thermal sensor.
static int laser_number
< Number of laser sensors
The main namespace for STDR GUI.
QTreeWidgetItem thermalSensorsNode
void loadSonar(QTreeWidgetItem *item)
Loads a specific sonar sensor from a file.
QIcon editIcon
Remove icon.
CCO2SensorPropertiesLoader co2SensorPropLoader
void treeItemClicked(QTreeWidgetItem *item, int column)
Called when a tree item is clicked.
stdr_msgs::RobotMsg new_robot_msg_
Current laser for highlight.
void drawSonars(void)
Draws the robot's sonars.
CRobotCreatorConnector(int argc, char **argv)
Default contructor.
QIcon loadIcon
Object of robot properties widget.
QTreeWidgetItem * current_footprint_point_
void setNewRobot(stdr_msgs::RobotMsg msg)
Sets the created robot.
void addRfidAntenna(void)
Adds an rfid antenna sensor in the new robot.
CThermalSensorPropertiesLoader thermalSensorPropLoader
void updateCO2SensorOpen(void)
Called when the refresh button of the properties widget is clicked.
void drawRfidAntennas(void)
Draws the robot's rfid antennas.
void setInitialPose(float x, float y)
Sets the robot's initial pose.
void editLaser(QTreeWidgetItem *item)
Edits a specific laser sensor based on a tree item. Initiates the laser sensor editor widget...
void eraseLaser(QTreeWidgetItem *item)
Erases a specific laser sensor based on a tree item.
void updateCO2Sensor(void)
Called when the update button of the properties widget is clicked.
void updateThermalSensorOpen(void)
Called when the refresh button of the properties widget is clicked.
void drawSoundSensors(void)
Draws the robot's rfid antennas.
void editRfid(QTreeWidgetItem *item)
Edits a specific rfid antenna sensor based on a tree item. Initiates the rfid antenna sensor editor w...
QImage robotPreviewImage
Add icon.
QTreeWidgetItem * current_co2_sensor_
unsigned int co2_sensor_hightlight_id_
void addCO2Sensor(void)
Adds a co2 sensor in the new robot.
static int sonar_number
Number of rfid antenna sensors.
QIcon removeIcon
Save icon.
void updateRfidAntennaOpen(void)
Called when the update button of the properties widget is clicked.
void editSoundSensor(QTreeWidgetItem *item)
Edits a specific sound sensor based on a tree item. \ Initiates the sound sensor editor widget...
void eraseThermalSensor(QTreeWidgetItem *item)
Erases a specific thermal sensor based on a tree item.
void editRobot(void)
Shows the edit robot widget.
void eraseFootprintPoint(QTreeWidgetItem *item)
Erases a footprint point in the new robot.
unsigned int rfid_antenna_hightlight_id_
Current rfid antenna for highlight.
void eraseSonar(QTreeWidgetItem *item)
Erases a specific sonar sensor based on a tree item.
void loadThermalSensor(QTreeWidgetItem *item)
Loads a specific thermal sensor from a file.
unsigned int laser_hightlight_id_
Current sonar for highlight.
static int co2_sensors_number
void updateRobotOpen(void)
Called when the refresh button of the properties widget is clicked.
void saveRobotPressed(stdr_msgs::RobotMsg newRobotMsg, QString file_name)
Emitted to save the robot in a yaml file.
void updateCO2SensorTree(QTreeWidgetItem *item, stdr_msgs::CO2SensorMsg l)
Updates a tree item with a specific co2 sensor.
void updateSonarOpen(void)
Called when the refresh button of the properties widget is clicked.
void loadCO2Sensor(QTreeWidgetItem *item)
Loads a specific co2 sensor from a file.