Skip to content
Snippets Groups Projects
Commit 1624a919 authored by marvin's avatar marvin
Browse files

Adapter supports new featuremodel.xml layout

parent 653e46cd
Branches
1 merge request!6Adapter custombot
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="turtlebot3_waffle_sim"> <robot xmlns:xacro="http://ros.org/wiki/xacro" name="turtlebot3_burger_sim">
<xacro:arg name="laser_visual" default="false" /> <xacro:arg name="laser_visual" default="false" />
<xacro:arg name="camera_visual" default="false" />
<xacro:arg name="imu_visual" default="false" /> <xacro:arg name="imu_visual" default="false" />
<gazebo reference="base_link"> <gazebo reference="base_link">
...@@ -30,7 +29,7 @@ ...@@ -30,7 +29,7 @@
<material>Gazebo/FlatBlack</material> <material>Gazebo/FlatBlack</material>
</gazebo> </gazebo>
<gazebo reference="caster_back_right_link"> <gazebo reference="caster_back_link">
<mu1>0.1</mu1> <mu1>0.1</mu1>
<mu2>0.1</mu2> <mu2>0.1</mu2>
<kp>1000000.0</kp> <kp>1000000.0</kp>
...@@ -40,26 +39,10 @@ ...@@ -40,26 +39,10 @@
<material>Gazebo/FlatBlack</material> <material>Gazebo/FlatBlack</material>
</gazebo> </gazebo>
<gazebo reference="caster_back_left_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>1000000.0</kp>
<kd>100.0</kd>
<minDepth>0.001</minDepth>
<maxVel>1.0</maxVel>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="imu_link">
<sensor type="imu" name="imu">
<always_on>true</always_on>
<visualize>$(arg imu_visual)</visualize>
</sensor>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo> <gazebo>
<plugin name="turtlebot3_waffle_controller" filename="libgazebo_ros_diff_drive.so"> <plugin name="turtlebot3_burger_controller" filename="libgazebo_ros_diff_drive.so">
<commandTopic>cmd_vel</commandTopic> <commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic> <odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame> <odometryFrame>odom</odometryFrame>
...@@ -73,7 +56,7 @@ ...@@ -73,7 +56,7 @@
<updateRate>30</updateRate> <updateRate>30</updateRate>
<leftJoint>wheel_left_joint</leftJoint> <leftJoint>wheel_left_joint</leftJoint>
<rightJoint>wheel_right_joint</rightJoint> <rightJoint>wheel_right_joint</rightJoint>
<wheelSeparation>0.287</wheelSeparation> <wheelSeparation>0.160</wheelSeparation>
<wheelDiameter>0.066</wheelDiameter> <wheelDiameter>0.066</wheelDiameter>
<wheelAcceleration>1</wheelAcceleration> <wheelAcceleration>1</wheelAcceleration>
<wheelTorque>10</wheelTorque> <wheelTorque>10</wheelTorque>
...@@ -110,11 +93,19 @@ ...@@ -110,11 +93,19 @@
</plugin> </plugin>
</gazebo> </gazebo>
<gazebo reference="base_scan">
<gazebo reference="imu_link">
<sensor type="imu" name="imu">
<always_on>true</always_on>
<visualize>false</visualize>
</sensor>
<material>Gazebo/FlatBlack</material>
</gazebo><gazebo reference="base_scan">
<material>Gazebo/FlatBlack</material> <material>Gazebo/FlatBlack</material>
<sensor type="ray" name="lds_lfcd_sensor"> <sensor type="ray" name="lds_lfcd_sensor">
<pose>0 0 0 0 0 0</pose> <pose>0 0 0 0 0 0</pose>
<visualize>$(arg laser_visual)</visualize> <visualize>false</visualize>
<update_rate>5</update_rate> <update_rate>5</update_rate>
<ray> <ray>
<scan> <scan>
...@@ -126,14 +117,14 @@ ...@@ -126,14 +117,14 @@
</horizontal> </horizontal>
</scan> </scan>
<range> <range>
<min>0.3</min> <min>0.120</min>
<max>5.2</max> <max>3.5</max>
<resolution>0.015</resolution> <resolution>0.015</resolution>
</range> </range>
<noise> <noise>
<type>gaussian</type> <type>gaussian</type>
<mean>0.0</mean> <mean>0.0</mean>
<stddev>0.09</stddev> <stddev>0.01</stddev>
</noise> </noise>
</ray> </ray>
<plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_laser.so"> <plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_laser.so">
...@@ -141,12 +132,10 @@ ...@@ -141,12 +132,10 @@
<frameName>base_scan</frameName> <frameName>base_scan</frameName>
</plugin> </plugin>
</sensor> </sensor>
</gazebo> </gazebo><gazebo reference="camera_rgb_frame">
<gazebo reference="camera_rgb_frame">
<sensor type="depth" name="realsense_R200"> <sensor type="depth" name="realsense_R200">
<always_on>true</always_on> <always_on>true</always_on>
<visualize>$(arg camera_visual)</visualize> <visualize>false</visualize>
<camera> <camera>
<horizontal_fov>1.3439</horizontal_fov> <horizontal_fov>1.3439</horizontal_fov>
<image> <image>
...@@ -185,6 +174,4 @@ ...@@ -185,6 +174,4 @@
<hackBaseline>0</hackBaseline> <hackBaseline>0</hackBaseline>
</plugin> </plugin>
</sensor> </sensor>
</gazebo> </gazebo></robot>
</robot>
Waffle Burger
\ No newline at end of file \ No newline at end of file
...@@ -10,10 +10,8 @@ import org.jdom2.xpath.*; ...@@ -10,10 +10,8 @@ import org.jdom2.xpath.*;
/** /**
* Takes a featuremodel.xml file generated using FeatureModelConfigurator and a given * Takes a featuremodel.xml file generated using FeatureModelConfigurator and a given ROS/ Gazebo .gazebo.xacro file.
* ROS/ Gazebo .gazebo.xacro file. * The .gazebo.xacro file is modified to support the features specified in the featuremodel.xml file.
* The .gazebo.xacro file is modified to support the features specified in the
* featuremodel.xml file.
*/ */
public class Adapter { public class Adapter {
...@@ -163,8 +161,6 @@ public class Adapter { ...@@ -163,8 +161,6 @@ public class Adapter {
* new ones from srcElements. * new ones from srcElements.
* (srcElements and destElements must be matching tags!) * (srcElements and destElements must be matching tags!)
* *
* TODO maybe add tags that are in srcElements but not yet in destElements
*
* @param srcElements Element list with new values * @param srcElements Element list with new values
* @param destElements Element list with values to be replaced * @param destElements Element list with values to be replaced
* @return true if reached deepest Element or false if not * @return true if reached deepest Element or false if not
...@@ -210,172 +206,158 @@ public class Adapter { ...@@ -210,172 +206,158 @@ public class Adapter {
* @param args * @param args
*/ */
public static void main(String[] args) { public static void main(String[] args) {
// System.out.println("Adapter started."); System.out.println("Adapter started.");
//
// try { try {
// //TODO##### Input ############################### //######### Input ###############################
// Document adapterConfig = readXml("./adapterconfig.xml"); Document adapterConfig = readXml("./adapterconfig.xml");
//
// String in_fmPath = getConfigVal(adapterConfig, "input/featuremodel", "path"); String in_fmPath = getConfigVal(adapterConfig, "input/featuremodel", "path");
// String in_scPath = getConfigVal(adapterConfig, "input/sensorconfig", "path"); String in_scPath = getConfigVal(adapterConfig, "input/sensorconfig", "path");
// String in_gmPath = getConfigVal(adapterConfig, "input/gazebomodel", "path"); String in_gmPath = getConfigVal(adapterConfig, "input/gazebomodel", "path");
// String out_gmPath = getConfigVal(adapterConfig, "output/gazebomodel", "path"); String out_gmPath = getConfigVal(adapterConfig, "output/gazebomodel", "path");
// String out_bnPath = getConfigVal(adapterConfig, "output/botname", "path"); String out_bnPath = getConfigVal(adapterConfig, "output/botname", "path");
// String in_fmName = getConfigVal(adapterConfig, "input/featuremodel", "name"); String in_fmName = getConfigVal(adapterConfig, "input/featuremodel", "name");
// String in_scName = ""; String in_gmName = "";
// String in_gmName = ""; String out_gmName = getConfigVal(adapterConfig, "output/gazebomodel", "name");
// String out_gmName = getConfigVal(adapterConfig, "output/gazebomodel", "name"); String out_bnName = getConfigVal(adapterConfig, "output/botname", "name");
// String out_bnName = getConfigVal(adapterConfig, "output/botname", "name");
// Document featureModel = readXml(in_fmPath+in_fmName);
// Document featureModel = readXml(in_fmPath+in_fmName); List<Document> sensorConfigList = new ArrayList<>();
// List<Document> sensorConfig = new ArrayList<>(); Document gazeboModel = null;
// Document gazeboModel = null;
// //Get the selected mode (either NO_CHANGE or Custom) as String
// //Get the selected mode (either NO_CHANGE or Custom) String mode = "";
// //TODO List<Attribute> modeList = xQueryAttributes(featureModel, "//mode/@param");
// String mode = ""; if(modeList.size()==1) {
// List<Attribute> modeList = xQueryAttributes(featureModel, "TODO get NO_CHANGE/ Custom parameter"); mode = modeList.get(0).getValue();
// if(modeList.size()==1) { }
// mode = modeList.get(0).getValue(); else {
// } System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
// else { System.exit(-1);
// System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed"); }
// System.exit(-1);
// } //Get all selected sensorconfig files as List<Document>
// switch(mode) {
// //Get all selected sensorconfig files case "NO_CHANGE":
// //TODO break;
// switch(mode) { case "Custom":
// case "NO_CHANGE": List<Attribute> sensorList = xQueryAttributes(featureModel, "//sensor/@name");
// break;
// case "Custom": List<String> scList = getFileNames(in_scPath);
// List<Attribute> sensorList = xQueryAttributes(featureModel, "TODO get all selected sensor parameters"); for(Attribute sensor : sensorList) {
// ////TODO oder weglassen boolean inDirectory = false;
//// List<String> scList = getFileNames(in_scPath); for(String fileName : scList) {
//// boolean inDirectory = true; if(fileName.equals(sensor.getValue()+".xml")) inDirectory = true;
//// for(Attribute sensor : sensorList) { }
//// for(String fileName : scList) { if(!inDirectory) {
//// if(!fileName.equals(sensor.getValue()+".xml")) inDirectory = false; System.err.println("Cannot handle \'"+sensor.getValue()+"\': No input file known.");
//// } System.exit(-1);
//// } }
//// if(!inDirectory) { }
//// System.err.println("");
//// System.exit(-1); for(Attribute sensor : sensorList) {
//// } sensorConfigList.add(readXml(in_scPath+sensor.getValue()+".xml"));
// //// }
// for(Attribute sensor : sensorList) { break;
// sensorConfig.add(readXml(in_scPath+sensor.getValue()+".xml")); default:
// } System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
// break; System.exit(-1);
// default: }
// System.err.println("Error: Unmatched case");
// System.exit(-1); //Get the selected .gazebo.xacro file as Document
// } String botName = "";
// List<Attribute> botList = xQueryAttributes(featureModel, "//templates/@name");
// //Get selected .gazebo.xacro file if(botList.size()==1) {
// //TODO botName = botList.get(0).getValue();
// //TODO generalize botList (remove "TurtleBot") }
// //List<Attribute> botList = xQueryAttributes(featureModel, "//module[@types='TurtleBot']/@name"); else {
// String botName = ""; System.err.println("Invalid input in \'"+in_fmName+"\': No or multiple bots selected.");
// List<Attribute> botList = xQueryAttributes(featureModel, "TODO get name of the bot"); System.exit(-1);
// if(botList.size()==1) { }
// botName = botList.get(0).getValue();
// } in_gmName = botName+".gazebo.xacro";
// else {
// System.err.println("Invalid input in "+in_fmName+": No or multiple bots selected"); List<String> gmList = getFileNames(in_gmPath);
// System.exit(-1); boolean inDirectory = false;
// } for(String fileName : gmList) {
// if(fileName.equals(in_gmName)) inDirectory = true;
// in_gmName = botName+".gazebo.xacro"; }
// if(!inDirectory) {
// List<String> gmList = getFileNames(in_gmPath); System.err.println("Cannot handle \'"+botName+"\': No input file known.");
// boolean inDirectory = false; System.exit(-1);
// for(String fileName : gmList) { }
// if(fileName.equals(in_gmName)) inDirectory = true;
// } gazeboModel = readXml(in_gmPath+in_gmName);
// if(!inDirectory) { //###############################################
// System.err.println("Cannot handle \'"+botName+"\': No input file known.");
// System.exit(-1);
// } //######### Operate on .gazebo.xacro ############
// switch(mode) {
// gazeboModel = readXml(in_gmPath+in_gmName); case "NO_CHANGE":
// //############################################### break;
// case "Custom":
// //Remove all existing sensors in template
// //TODO##### Operate on .gazebo.xacro ############ NOCH NICHT UEBERARBEITET List<Element> removableSensorsList = xQueryElements(gazeboModel, "//sensor");
// List<Element> cSensorList = xQueryElements(sensorConfig, "//sensor");
// List<Element> gSensorList = xQueryElements(gazeboModel, "//sensor"); for(Element sensor : removableSensorsList) {
// boolean match = false; Element entry = sensor.getParentElement();
// if(entry.getName().equals("gazebo")) {
// if(cSensorList.isEmpty()) { entry.detach();
// System.out.println("No new sensor values in "+in_scName); }
// System.exit(-1); else {
// } System.out.println("Found a <sensor> element in \'"+in_gmName+
// if(gSensorList.isEmpty()) { "\' that does not have a <gazebo> element as immediate parent. It was not removed, as this input is unexpected.");
// System.out.println("No sensors found in "+in_gmName); }
// System.exit(-1); }
// }
// //Insert selected sensors into template
// for(Element cSensor : cSensorList) { for(Document sensorConfig : sensorConfigList) {
// for(Element gSensor : gSensorList) { List<Element> sensorList = xQueryElements(sensorConfig, "//gazebo");
// if(equalTag(cSensor, gSensor)) { if(sensorList.size()==1) {
// replace(cSensor.getChildren(), gSensor.getChildren()); Element sensor = sensorList.get(0);
// match = true;
// } //Warn if a sensor still contains $(arg ...) values
// } List<Element> tagList = xQueryElements(sensor, "//*");
// } for(Element tag : tagList) {
// String text = tag.getText();
// if(!match) System.out.println("No matching sensors could be found in "+in_scName+" and "+in_gmName); if(text.contains("$")) {
// //############################################### System.out.println("Warning: a sensorconfig file still contains an abstract value: \'"+text+
// "\'. It should be replaced with a set value, or the output .gazebo.xacro will likely be broken.");
// }
// //######### Output result ####################### }
// saveAsXml(gazeboModel, out_gmPath+out_gmName);
// sensor.detach();
// BufferedWriter bufferedWriter = new BufferedWriter(new FileWriter(out_bnPath+out_bnName)); gazeboModel.getRootElement().addContent(sensor);
// bufferedWriter.write(botName); }
// bufferedWriter.close(); else {
// //############################################### System.err.println("Invalid input. At least one sensorconfig file contains no or multiple <gazebo> entries.");
// } System.exit(-1);
// catch (JDOMException | IOException e) { }
// e.printStackTrace(); }
// } break;
default:
System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
System.exit(-1);
}
//###############################################
//######### Output result #######################
saveAsXml(gazeboModel, out_gmPath+out_gmName);
BufferedWriter bufferedWriter = new BufferedWriter(new FileWriter(out_bnPath+out_bnName));
bufferedWriter.write(botName);
bufferedWriter.close();
//###############################################
}
catch (JDOMException | IOException e) {
e.printStackTrace();
}
System.out.println("Adapter finished."); System.out.println("Adapter finished.");
} }
} }
//Example dump
//hard-coded and only for demo purposes
//List<Element> cSensorList = xQueryElements(sensorConfig, "//sensor[@type='ray' and @name='lds_lfcd_sensor']");
//Element cSensor = cSensorList.get(0);
//
//List<Element> gSensorList = xQueryElements(gazeboModel, "//sensor[@type='ray' and @name='lds_lfcd_sensor']");
//Element gSensor = gSensorList.get(0);
//
//String new_min = cSensor.getChild("range").getChild("min").getText();
//String new_max = cSensor.getChild("range").getChild("max").getText();
//
//gSensor.getChild("ray").getChild("range").getChild("min").setText(new_min);
//gSensor.getChild("ray").getChild("range").getChild("max").setText(new_max);
//XPathExamples
//XPathFactory xFactory = XPathFactory.instance();
//XPathExpression<Element> xExpr = xFactory.compile("robot/gazebo/sensor/ray/range/min", Filters.element());
//Element test = xExpr.evaluateFirst(gazeboModel);
//List<Element> test2 = searchAllElements(gazeboModel, "min");
//List<Element> test3 = searchAllElements(gazeboModel, "max");
//Element test4 = searchFirstElement(gazeboModel, "plugin");
//List<Attribute> test5 = xQueryAttributes(gazeboModel, "(//plugin)[1]/@*");
//
//if(test != null) xmlOutput.output(test, System.out);
//System.out.println("\n");
//xmlOutput.output(test2, System.out);
//System.out.println("\n");
//xmlOutput.output(test3, System.out);
//System.out.println("\n");
//if(test4 != null) xmlOutput.output(test4, System.out);
//System.out.println("\n");
//for(Attribute a : test5) System.out.println(a.getName()+"="+a.getValue());
...@@ -10,10 +10,8 @@ import org.jdom2.xpath.*; ...@@ -10,10 +10,8 @@ import org.jdom2.xpath.*;
/** /**
* Takes a featuremodel.xml file generated using FeatureModelConfigurator and a given * Takes a featuremodel.xml file generated using FeatureModelConfigurator and a given ROS/ Gazebo .gazebo.xacro file.
* ROS/ Gazebo .gazebo.xacro file. * The .gazebo.xacro file is modified to support the features specified in the featuremodel.xml file.
* The .gazebo.xacro file is modified to support the features specified in the
* featuremodel.xml file.
*/ */
public class Adapter { public class Adapter {
...@@ -163,8 +161,6 @@ public class Adapter { ...@@ -163,8 +161,6 @@ public class Adapter {
* new ones from srcElements. * new ones from srcElements.
* (srcElements and destElements must be matching tags!) * (srcElements and destElements must be matching tags!)
* *
* TODO maybe add tags that are in srcElements but not yet in destElements
*
* @param srcElements Element list with new values * @param srcElements Element list with new values
* @param destElements Element list with values to be replaced * @param destElements Element list with values to be replaced
* @return true if reached deepest Element or false if not * @return true if reached deepest Element or false if not
...@@ -210,172 +206,158 @@ public class Adapter { ...@@ -210,172 +206,158 @@ public class Adapter {
* @param args * @param args
*/ */
public static void main(String[] args) { public static void main(String[] args) {
// System.out.println("Adapter started."); System.out.println("Adapter started.");
//
// try { try {
// //TODO##### Input ############################### //######### Input ###############################
// Document adapterConfig = readXml("./adapterconfig.xml"); Document adapterConfig = readXml("./adapterconfig.xml");
//
// String in_fmPath = getConfigVal(adapterConfig, "input/featuremodel", "path"); String in_fmPath = getConfigVal(adapterConfig, "input/featuremodel", "path");
// String in_scPath = getConfigVal(adapterConfig, "input/sensorconfig", "path"); String in_scPath = getConfigVal(adapterConfig, "input/sensorconfig", "path");
// String in_gmPath = getConfigVal(adapterConfig, "input/gazebomodel", "path"); String in_gmPath = getConfigVal(adapterConfig, "input/gazebomodel", "path");
// String out_gmPath = getConfigVal(adapterConfig, "output/gazebomodel", "path"); String out_gmPath = getConfigVal(adapterConfig, "output/gazebomodel", "path");
// String out_bnPath = getConfigVal(adapterConfig, "output/botname", "path"); String out_bnPath = getConfigVal(adapterConfig, "output/botname", "path");
// String in_fmName = getConfigVal(adapterConfig, "input/featuremodel", "name"); String in_fmName = getConfigVal(adapterConfig, "input/featuremodel", "name");
// String in_scName = ""; String in_gmName = "";
// String in_gmName = ""; String out_gmName = getConfigVal(adapterConfig, "output/gazebomodel", "name");
// String out_gmName = getConfigVal(adapterConfig, "output/gazebomodel", "name"); String out_bnName = getConfigVal(adapterConfig, "output/botname", "name");
// String out_bnName = getConfigVal(adapterConfig, "output/botname", "name");
// Document featureModel = readXml(in_fmPath+in_fmName);
// Document featureModel = readXml(in_fmPath+in_fmName); List<Document> sensorConfigList = new ArrayList<>();
// List<Document> sensorConfig = new ArrayList<>(); Document gazeboModel = null;
// Document gazeboModel = null;
// //Get the selected mode (either NO_CHANGE or Custom) as String
// //Get the selected mode (either NO_CHANGE or Custom) String mode = "";
// //TODO List<Attribute> modeList = xQueryAttributes(featureModel, "//mode/@param");
// String mode = ""; if(modeList.size()==1) {
// List<Attribute> modeList = xQueryAttributes(featureModel, "TODO get NO_CHANGE/ Custom parameter"); mode = modeList.get(0).getValue();
// if(modeList.size()==1) { }
// mode = modeList.get(0).getValue(); else {
// } System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
// else { System.exit(-1);
// System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed"); }
// System.exit(-1);
// } //Get all selected sensorconfig files as List<Document>
// switch(mode) {
// //Get all selected sensorconfig files case "NO_CHANGE":
// //TODO break;
// switch(mode) { case "Custom":
// case "NO_CHANGE": List<Attribute> sensorList = xQueryAttributes(featureModel, "//sensor/@name");
// break;
// case "Custom": List<String> scList = getFileNames(in_scPath);
// List<Attribute> sensorList = xQueryAttributes(featureModel, "TODO get all selected sensor parameters"); for(Attribute sensor : sensorList) {
// ////TODO oder weglassen boolean inDirectory = false;
//// List<String> scList = getFileNames(in_scPath); for(String fileName : scList) {
//// boolean inDirectory = true; if(fileName.equals(sensor.getValue()+".xml")) inDirectory = true;
//// for(Attribute sensor : sensorList) { }
//// for(String fileName : scList) { if(!inDirectory) {
//// if(!fileName.equals(sensor.getValue()+".xml")) inDirectory = false; System.err.println("Cannot handle \'"+sensor.getValue()+"\': No input file known.");
//// } System.exit(-1);
//// } }
//// if(!inDirectory) { }
//// System.err.println("");
//// System.exit(-1); for(Attribute sensor : sensorList) {
//// } sensorConfigList.add(readXml(in_scPath+sensor.getValue()+".xml"));
// //// }
// for(Attribute sensor : sensorList) { break;
// sensorConfig.add(readXml(in_scPath+sensor.getValue()+".xml")); default:
// } System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
// break; System.exit(-1);
// default: }
// System.err.println("Error: Unmatched case");
// System.exit(-1); //Get the selected .gazebo.xacro file as Document
// } String botName = "";
// List<Attribute> botList = xQueryAttributes(featureModel, "//templates/@name");
// //Get selected .gazebo.xacro file if(botList.size()==1) {
// //TODO botName = botList.get(0).getValue();
// //TODO generalize botList (remove "TurtleBot") }
// //List<Attribute> botList = xQueryAttributes(featureModel, "//module[@types='TurtleBot']/@name"); else {
// String botName = ""; System.err.println("Invalid input in \'"+in_fmName+"\': No or multiple bots selected.");
// List<Attribute> botList = xQueryAttributes(featureModel, "TODO get name of the bot"); System.exit(-1);
// if(botList.size()==1) { }
// botName = botList.get(0).getValue();
// } in_gmName = botName+".gazebo.xacro";
// else {
// System.err.println("Invalid input in "+in_fmName+": No or multiple bots selected"); List<String> gmList = getFileNames(in_gmPath);
// System.exit(-1); boolean inDirectory = false;
// } for(String fileName : gmList) {
// if(fileName.equals(in_gmName)) inDirectory = true;
// in_gmName = botName+".gazebo.xacro"; }
// if(!inDirectory) {
// List<String> gmList = getFileNames(in_gmPath); System.err.println("Cannot handle \'"+botName+"\': No input file known.");
// boolean inDirectory = false; System.exit(-1);
// for(String fileName : gmList) { }
// if(fileName.equals(in_gmName)) inDirectory = true;
// } gazeboModel = readXml(in_gmPath+in_gmName);
// if(!inDirectory) { //###############################################
// System.err.println("Cannot handle \'"+botName+"\': No input file known.");
// System.exit(-1);
// } //######### Operate on .gazebo.xacro ############
// switch(mode) {
// gazeboModel = readXml(in_gmPath+in_gmName); case "NO_CHANGE":
// //############################################### break;
// case "Custom":
// //Remove all existing sensors in template
// //TODO##### Operate on .gazebo.xacro ############ NOCH NICHT UEBERARBEITET List<Element> removableSensorsList = xQueryElements(gazeboModel, "//sensor");
// List<Element> cSensorList = xQueryElements(sensorConfig, "//sensor");
// List<Element> gSensorList = xQueryElements(gazeboModel, "//sensor"); for(Element sensor : removableSensorsList) {
// boolean match = false; Element entry = sensor.getParentElement();
// if(entry.getName().equals("gazebo")) {
// if(cSensorList.isEmpty()) { entry.detach();
// System.out.println("No new sensor values in "+in_scName); }
// System.exit(-1); else {
// } System.out.println("Found a <sensor> element in \'"+in_gmName+
// if(gSensorList.isEmpty()) { "\' that does not have a <gazebo> element as immediate parent. It was not removed, as this input is unexpected.");
// System.out.println("No sensors found in "+in_gmName); }
// System.exit(-1); }
// }
// //Insert selected sensors into template
// for(Element cSensor : cSensorList) { for(Document sensorConfig : sensorConfigList) {
// for(Element gSensor : gSensorList) { List<Element> sensorList = xQueryElements(sensorConfig, "//gazebo");
// if(equalTag(cSensor, gSensor)) { if(sensorList.size()==1) {
// replace(cSensor.getChildren(), gSensor.getChildren()); Element sensor = sensorList.get(0);
// match = true;
// } //Warn if a sensor still contains $(arg ...) values
// } List<Element> tagList = xQueryElements(sensor, "//*");
// } for(Element tag : tagList) {
// String text = tag.getText();
// if(!match) System.out.println("No matching sensors could be found in "+in_scName+" and "+in_gmName); if(text.contains("$")) {
// //############################################### System.out.println("Warning: a sensorconfig file still contains an abstract value: \'"+text+
// "\'. It should be replaced with a set value, or the output .gazebo.xacro will likely be broken.");
// }
// //######### Output result ####################### }
// saveAsXml(gazeboModel, out_gmPath+out_gmName);
// sensor.detach();
// BufferedWriter bufferedWriter = new BufferedWriter(new FileWriter(out_bnPath+out_bnName)); gazeboModel.getRootElement().addContent(sensor);
// bufferedWriter.write(botName); }
// bufferedWriter.close(); else {
// //############################################### System.err.println("Invalid input. At least one sensorconfig file contains no or multiple <gazebo> entries.");
// } System.exit(-1);
// catch (JDOMException | IOException e) { }
// e.printStackTrace(); }
// } break;
default:
System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
System.exit(-1);
}
//###############################################
//######### Output result #######################
saveAsXml(gazeboModel, out_gmPath+out_gmName);
BufferedWriter bufferedWriter = new BufferedWriter(new FileWriter(out_bnPath+out_bnName));
bufferedWriter.write(botName);
bufferedWriter.close();
//###############################################
}
catch (JDOMException | IOException e) {
e.printStackTrace();
}
System.out.println("Adapter finished."); System.out.println("Adapter finished.");
} }
} }
//Example dump
//hard-coded and only for demo purposes
//List<Element> cSensorList = xQueryElements(sensorConfig, "//sensor[@type='ray' and @name='lds_lfcd_sensor']");
//Element cSensor = cSensorList.get(0);
//
//List<Element> gSensorList = xQueryElements(gazeboModel, "//sensor[@type='ray' and @name='lds_lfcd_sensor']");
//Element gSensor = gSensorList.get(0);
//
//String new_min = cSensor.getChild("range").getChild("min").getText();
//String new_max = cSensor.getChild("range").getChild("max").getText();
//
//gSensor.getChild("ray").getChild("range").getChild("min").setText(new_min);
//gSensor.getChild("ray").getChild("range").getChild("max").setText(new_max);
//XPathExamples
//XPathFactory xFactory = XPathFactory.instance();
//XPathExpression<Element> xExpr = xFactory.compile("robot/gazebo/sensor/ray/range/min", Filters.element());
//Element test = xExpr.evaluateFirst(gazeboModel);
//List<Element> test2 = searchAllElements(gazeboModel, "min");
//List<Element> test3 = searchAllElements(gazeboModel, "max");
//Element test4 = searchFirstElement(gazeboModel, "plugin");
//List<Attribute> test5 = xQueryAttributes(gazeboModel, "(//plugin)[1]/@*");
//
//if(test != null) xmlOutput.output(test, System.out);
//System.out.println("\n");
//xmlOutput.output(test2, System.out);
//System.out.println("\n");
//xmlOutput.output(test3, System.out);
//System.out.println("\n");
//if(test4 != null) xmlOutput.output(test4, System.out);
//System.out.println("\n");
//for(Attribute a : test5) System.out.println(a.getName()+"="+a.getValue());
...@@ -10,10 +10,8 @@ import org.jdom2.xpath.*; ...@@ -10,10 +10,8 @@ import org.jdom2.xpath.*;
/** /**
* Takes a featuremodel.xml file generated using FeatureModelConfigurator and a given * Takes a featuremodel.xml file generated using FeatureModelConfigurator and a given ROS/ Gazebo .gazebo.xacro file.
* ROS/ Gazebo .gazebo.xacro file. * The .gazebo.xacro file is modified to support the features specified in the featuremodel.xml file.
* The .gazebo.xacro file is modified to support the features specified in the
* featuremodel.xml file.
*/ */
public class Adapter { public class Adapter {
...@@ -163,8 +161,6 @@ public class Adapter { ...@@ -163,8 +161,6 @@ public class Adapter {
* new ones from srcElements. * new ones from srcElements.
* (srcElements and destElements must be matching tags!) * (srcElements and destElements must be matching tags!)
* *
* TODO maybe add tags that are in srcElements but not yet in destElements
*
* @param srcElements Element list with new values * @param srcElements Element list with new values
* @param destElements Element list with values to be replaced * @param destElements Element list with values to be replaced
* @return true if reached deepest Element or false if not * @return true if reached deepest Element or false if not
...@@ -213,7 +209,7 @@ public class Adapter { ...@@ -213,7 +209,7 @@ public class Adapter {
System.out.println("Adapter started."); System.out.println("Adapter started.");
try { try {
//TODO##### Input ############################### //######### Input ###############################
Document adapterConfig = readXml("./adapterconfig.xml"); Document adapterConfig = readXml("./adapterconfig.xml");
String in_fmPath = getConfigVal(adapterConfig, "input/featuremodel", "path"); String in_fmPath = getConfigVal(adapterConfig, "input/featuremodel", "path");
...@@ -222,67 +218,61 @@ public class Adapter { ...@@ -222,67 +218,61 @@ public class Adapter {
String out_gmPath = getConfigVal(adapterConfig, "output/gazebomodel", "path"); String out_gmPath = getConfigVal(adapterConfig, "output/gazebomodel", "path");
String out_bnPath = getConfigVal(adapterConfig, "output/botname", "path"); String out_bnPath = getConfigVal(adapterConfig, "output/botname", "path");
String in_fmName = getConfigVal(adapterConfig, "input/featuremodel", "name"); String in_fmName = getConfigVal(adapterConfig, "input/featuremodel", "name");
String in_scName = "";
String in_gmName = ""; String in_gmName = "";
String out_gmName = getConfigVal(adapterConfig, "output/gazebomodel", "name"); String out_gmName = getConfigVal(adapterConfig, "output/gazebomodel", "name");
String out_bnName = getConfigVal(adapterConfig, "output/botname", "name"); String out_bnName = getConfigVal(adapterConfig, "output/botname", "name");
Document featureModel = readXml(in_fmPath+in_fmName); Document featureModel = readXml(in_fmPath+in_fmName);
List<Document> sensorConfig = new ArrayList<>(); List<Document> sensorConfigList = new ArrayList<>();
Document gazeboModel = null; Document gazeboModel = null;
//Get the selected mode (either NO_CHANGE or Custom) //Get the selected mode (either NO_CHANGE or Custom) as String
//TODO
String mode = ""; String mode = "";
List<Attribute> modeList = xQueryAttributes(featureModel, "TODO get NO_CHANGE/ Custom parameter"); List<Attribute> modeList = xQueryAttributes(featureModel, "//mode/@param");
if(modeList.size()==1) { if(modeList.size()==1) {
mode = modeList.get(0).getValue(); mode = modeList.get(0).getValue();
} }
else { else {
System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed"); System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
System.exit(-1); System.exit(-1);
} }
//Get all selected sensorconfig files //Get all selected sensorconfig files as List<Document>
//TODO
switch(mode) { switch(mode) {
case "NO_CHANGE": case "NO_CHANGE":
break; break;
case "Custom": case "Custom":
List<Attribute> sensorList = xQueryAttributes(featureModel, "TODO get all selected sensor parameters"); List<Attribute> sensorList = xQueryAttributes(featureModel, "//sensor/@name");
////TODO oder weglassen
// List<String> scList = getFileNames(in_scPath); List<String> scList = getFileNames(in_scPath);
// boolean inDirectory = true; for(Attribute sensor : sensorList) {
// for(Attribute sensor : sensorList) { boolean inDirectory = false;
// for(String fileName : scList) { for(String fileName : scList) {
// if(!fileName.equals(sensor.getValue()+".xml")) inDirectory = false; if(fileName.equals(sensor.getValue()+".xml")) inDirectory = true;
// } }
// } if(!inDirectory) {
// if(!inDirectory) { System.err.println("Cannot handle \'"+sensor.getValue()+"\': No input file known.");
// System.err.println(""); System.exit(-1);
// System.exit(-1); }
// } }
////
for(Attribute sensor : sensorList) { for(Attribute sensor : sensorList) {
sensorConfig.add(readXml(in_scPath+sensor.getValue()+".xml")); sensorConfigList.add(readXml(in_scPath+sensor.getValue()+".xml"));
} }
break; break;
default: default:
System.err.println("Error: Unmatched case"); System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
System.exit(-1); System.exit(-1);
} }
//Get selected .gazebo.xacro file //Get the selected .gazebo.xacro file as Document
//TODO
//TODO generalize botList (remove "TurtleBot")
//List<Attribute> botList = xQueryAttributes(featureModel, "//module[@types='TurtleBot']/@name");
String botName = ""; String botName = "";
List<Attribute> botList = xQueryAttributes(featureModel, "TODO get name of the bot"); List<Attribute> botList = xQueryAttributes(featureModel, "//templates/@name");
if(botList.size()==1) { if(botList.size()==1) {
botName = botList.get(0).getValue(); botName = botList.get(0).getValue();
} }
else { else {
System.err.println("Invalid input in "+in_fmName+": No or multiple bots selected"); System.err.println("Invalid input in \'"+in_fmName+"\': No or multiple bots selected.");
System.exit(-1); System.exit(-1);
} }
...@@ -302,30 +292,54 @@ public class Adapter { ...@@ -302,30 +292,54 @@ public class Adapter {
//############################################### //###############################################
//TODO##### Operate on .gazebo.xacro ############ NOCH NICHT UEBERARBEITET //######### Operate on .gazebo.xacro ############
List<Element> cSensorList = xQueryElements(sensorConfig, "//sensor"); switch(mode) {
List<Element> gSensorList = xQueryElements(gazeboModel, "//sensor"); case "NO_CHANGE":
boolean match = false; break;
case "Custom":
if(cSensorList.isEmpty()) { //Remove all existing sensors in template
System.out.println("No new sensor values in "+in_scName); List<Element> removableSensorsList = xQueryElements(gazeboModel, "//sensor");
System.exit(-1);
} for(Element sensor : removableSensorsList) {
if(gSensorList.isEmpty()) { Element entry = sensor.getParentElement();
System.out.println("No sensors found in "+in_gmName); if(entry.getName().equals("gazebo")) {
System.exit(-1); entry.detach();
} }
else {
for(Element cSensor : cSensorList) { System.out.println("Found a <sensor> element in \'"+in_gmName+
for(Element gSensor : gSensorList) { "\' that does not have a <gazebo> element as immediate parent. It was not removed, as this input is unexpected.");
if(equalTag(cSensor, gSensor)) { }
replace(cSensor.getChildren(), gSensor.getChildren());
match = true;
} }
}
//Insert selected sensors into template
for(Document sensorConfig : sensorConfigList) {
List<Element> sensorList = xQueryElements(sensorConfig, "//gazebo");
if(sensorList.size()==1) {
Element sensor = sensorList.get(0);
//Warn if a sensor still contains $(arg ...) values
List<Element> tagList = xQueryElements(sensor, "//*");
for(Element tag : tagList) {
String text = tag.getText();
if(text.contains("$")) {
System.out.println("Warning: a sensorconfig file still contains an abstract value: \'"+text+
"\'. It should be replaced with a set value, or the output .gazebo.xacro will likely be broken.");
}
}
sensor.detach();
gazeboModel.getRootElement().addContent(sensor);
}
else {
System.err.println("Invalid input. At least one sensorconfig file contains no or multiple <gazebo> entries.");
System.exit(-1);
}
}
break;
default:
System.err.println("Invalid input in \'"+in_fmName+"\': NO_CHANGE/ Custom parameter could not be parsed.");
System.exit(-1);
} }
if(!match) System.out.println("No matching sensors could be found in "+in_scName+" and "+in_gmName);
//############################################### //###############################################
...@@ -346,36 +360,4 @@ public class Adapter { ...@@ -346,36 +360,4 @@ public class Adapter {
} }
//Example dump
//hard-coded and only for demo purposes
//List<Element> cSensorList = xQueryElements(sensorConfig, "//sensor[@type='ray' and @name='lds_lfcd_sensor']");
//Element cSensor = cSensorList.get(0);
//
//List<Element> gSensorList = xQueryElements(gazeboModel, "//sensor[@type='ray' and @name='lds_lfcd_sensor']");
//Element gSensor = gSensorList.get(0);
//
//String new_min = cSensor.getChild("range").getChild("min").getText();
//String new_max = cSensor.getChild("range").getChild("max").getText();
//
//gSensor.getChild("ray").getChild("range").getChild("min").setText(new_min);
//gSensor.getChild("ray").getChild("range").getChild("max").setText(new_max);
//XPathExamples
//XPathFactory xFactory = XPathFactory.instance();
//XPathExpression<Element> xExpr = xFactory.compile("robot/gazebo/sensor/ray/range/min", Filters.element());
//Element test = xExpr.evaluateFirst(gazeboModel);
//List<Element> test2 = searchAllElements(gazeboModel, "min");
//List<Element> test3 = searchAllElements(gazeboModel, "max");
//Element test4 = searchFirstElement(gazeboModel, "plugin");
//List<Attribute> test5 = xQueryAttributes(gazeboModel, "(//plugin)[1]/@*");
//
//if(test != null) xmlOutput.output(test, System.out);
//System.out.println("\n");
//xmlOutput.output(test2, System.out);
//System.out.println("\n");
//xmlOutput.output(test3, System.out);
//System.out.println("\n");
//if(test4 != null) xmlOutput.output(test4, System.out);
//System.out.println("\n");
//for(Attribute a : test5) System.out.println(a.getName()+"="+a.getValue());
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment