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


pddl_planner_viewer
Author(s): Ryohei Ueda (ueda@jsk.t.u-tokyo.ac.jp)
autogenerated on Mon Sep 14 2015 14:00:48