pddl_planner_viewer.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 import roslib; roslib.load_manifest('pddl_planner_viewer')
00004 import rospy
00005 import pddl_msgs
00006 from pddl_msgs.msg import *
00007 import actionlib
00008 
00009 import wx
00010 
00011 class PDDLPlannerViewer(wx.Frame):
00012     def __init__(self, parent, id, title):
00013         wx.Frame.__init__(self, parent, id, title, size=(400, 500))
00014 
00015         # make a root panel and sizer
00016         self._panel = wx.Panel(self, -1)
00017         self._sizer = wx.GridBagSizer(4, 4)
00018         # static text
00019         state_text = wx.StaticText(self._panel, -1,
00020                                    'Initial States which are True')
00021         plan_text = wx.StaticText(self._panel, -1, 'Plan')
00022         self._problem_text = wx.StaticText(self._panel, -1, 'problem name: ')
00023         self._domain_text = wx.StaticText(self._panel, -1, 'domain name: ')
00024         self._sizer.Add(self._problem_text, (0, 0),
00025                         flag=wx.TOP | wx.LEFT | wx.BOTTOM, border=5)
00026         self._sizer.Add(self._domain_text, (1, 0),
00027                         flag=wx.TOP | wx.LEFT | wx.BOTTOM, border=5)
00028         self._sizer.Add(state_text, (2, 0),
00029                         flag=wx.TOP | wx.LEFT | wx.BOTTOM, border=5)
00030         self._sizer.Add(plan_text, (8, 0),
00031                         flag=wx.TOP | wx.LEFT | wx.BOTTOM, border=5)
00032         
00033         self._state_list = wx.ListBox(self._panel, -1, style=wx.LB_ALWAYS_SB)
00034         self._sizer.Add(self._state_list, (3, 0), (5, 3),
00035                         wx.EXPAND | wx.LEFT | wx.RIGHT, 5)
00036         
00037         
00038         self._plan_list = wx.ListBox(self._panel, -1, style=wx.LB_ALWAYS_SB)
00039         self._sizer.Add(self._plan_list, (9, 0), (3, 3),
00040                         wx.EXPAND | wx.LEFT | wx.RIGHT, 5)
00041         
00042         self._sizer.AddGrowableCol(0)
00043         self._sizer.AddGrowableRow(3)
00044         self._sizer.AddGrowableRow(9)
00045         self._sizer.SetEmptyCellSize((5, 5))
00046         self._panel.SetSizer(self._sizer)
00047         self._need_to_refresh_goal = False
00048         self._need_to_refresh_plan_results = False
00049         
00050         self.Bind(wx.EVT_IDLE, self.update_plan)
00051         rospy.Subscriber("pddl_planner/result", PDDLPlannerActionResult,
00052                          self.result_listen)
00053         rospy.Subscriber("pddl_planner/goal", PDDLPlannerActionGoal,
00054                          self.goal_listen)
00055         self.Centre()
00056         self.Show(True)
00057         
00058     def goal_listen(self, data):
00059         self._goal = data.goal
00060         self._need_to_refresh_goal = True
00061         
00062     # result listener
00063     def result_listen(self, data):
00064         self._plan_results = data.result.sequence
00065         self._need_to_refresh_plan_results = True
00066 
00067         
00068     def update_plan(self, dummy):
00069         if self._need_to_refresh_plan_results:
00070             self._plan_list.Clear()
00071             i = 0
00072             for r in self._plan_results:
00073                 self._plan_list.Append(str(i) + " " + 
00074                                        str(tuple([r.action]) + tuple(r.args)))
00075                 i = i + 1
00076             self._need_to_refresh_plan_results = False
00077             
00078         if self._need_to_refresh_goal:
00079             self._state_list.Clear()
00080             for i in self._goal.problem.initial:
00081                 self._state_list.Append(str(i))
00082             self._need_to_refresh_goal = False
00083             self._problem_text.SetLabel('problem name: '
00084                                         + self._goal.problem.name)
00085             self._domain_text.SetLabel('domain name: '
00086                                         + self._goal.domain.name)
00087 
00088 
00089 # main
00090 if __name__ == '__main__':
00091     rospy.init_node('pddl_planner_viewer')
00092     app = wx.App()
00093     PDDLPlannerViewer(None, -1, 'PDDL Plan')
00094     app.MainLoop()
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pddl_planner_viewer
Author(s): Ryohei Ueda (ueda@jsk.t.u-tokyo.ac.jp)
autogenerated on Sun Mar 24 2013 01:01:50