====== Use KnowRob from your program ======
~~NOTOC~~
\\
^ This page describes the 'catkinized' version of KnowRob that has been converted to the [[http://wiki.ros.org/catkin/|catkin buildsystem]] and the new [[http://wiki.ros.org/rosjava|rosjava]]. The documentation for older versions can be found [[/doc/interact_with_knowrob_via_ros?rev=1401968328|here]].^
\\
The interactive Prolog shell that [[http://ros.org/wiki/rosprolog|rosprolog]] provides is good for exploring KnowRob, visualizing knowledge, developing new functions and debugging Prolog code. However, if you would like to use KnowRob in your robot's control program, you need a way to send queries from your program. This functionality is provided by the [[http://ros.org/wiki/json_prolog|json_prolog]] package. It provides a service that exposes a Prolog shell via ROS. You can run the //json_prolog// service using a launch file such as the following (which can be found in //knowrob_map_data/launch/ccrl2_semantic_map.launch//).
The //json_prolog_node// reads two optional ROS parameters for the initial package to be loaded (that you also give as argument when starting //rosprolog//) and a command to be executed at startup, for example for parsing an OWL file.
===== Client libraries =====
The communication with the //json_prolog// service uses a [[http://json.org/|JSON-encoded]] format for representing the Prolog terms that form the query. While you can construct these terms manually and call the service directly, it is usally much easier to use one of the provided client libraries. There are libraries for Python, C++, Java and Lisp. Example clients are available in the //json_prolog/examples// folder; below is the code for sending KnowRob queries from Python via //json_prolog//.
==== Python client ====
#!/usr/bin/env python
import roslib; roslib.load_manifest('json_prolog')
import rospy
import json_prolog
if __name__ == '__main__':
rospy.init_node('test_json_prolog')
prolog = json_prolog.Prolog()
query = prolog.query("member(A, [1, 2, 3, 4]), B = ['x', A]")
for solution in query.solutions():
print 'Found solution. A = %s, B = %s' % (solution['A'], solution['B'])
query.finish()
==== C++ client ====
#include
#include
#include
#include
using namespace std;
using namespace json_prolog;
int main(int argc, char *argv[])
{
ros::init(argc, argv, "test_json_prolog");
Prolog pl;
PrologQueryProxy bdgs = pl.query("member(A, [1, 2, 3, 4]), B = ['x', A], C = foo(bar, A, B)");
for(PrologQueryProxy::iterator it=bdgs.begin();
it != bdgs.end(); it++)
{
PrologBindings bdg = *it;
cout << "Found solution: " << (bool)(it == bdgs.end()) << endl;
cout << "A = "<< bdg["A"] << endl;
cout << "B = " << bdg["B"] << endl;
cout << "C = " << bdg["C"] << endl;
}
return 0;
}
==== Java client ====
package org.knowrob.json_prolog;
import org.knowrob.json_prolog.Prolog;
import org.knowrob.json_prolog.PrologBindings;
import org.knowrob.json_prolog.PrologQueryProxy;
import org.knowrob.utils.ros.RosUtilities;
public class JSONPrologTestClient {
public static void main(String args[]) {
Prolog pl = new Prolog();
RosUtilities.runRosjavaNode(pl, new String[]{"org.knowrob.json_prolog.Prolog"});
PrologQueryProxy bdgs = pl.query("member(A, [1, 2, 3, 4]), B = ['x', A], C = foo(bar, A, B)");
for(PrologBindings bdg : bdgs) {
System.out.println("Found solution: ");
System.out.println("A = " + bdg.getBdgs_().get("A") );
System.out.println("B = " + bdg.getBdgs_().get("B") );
System.out.println("C = " + bdg.getBdgs_().get("C") );
}
}
}