Skip to content

Commit

Permalink
euslisp/actionlib.l: set queue_size following to action_server_imp.h …
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Nov 23, 2015
1 parent 76cfe31 commit 87d0d62
Showing 1 changed file with 15 additions and 15 deletions.
30 changes: 15 additions & 15 deletions roseus/euslisp/actionlib.l
Original file line number Diff line number Diff line change
Expand Up @@ -88,23 +88,23 @@
(setq action-goal-class (class (send action-spec :action_goal))
action-result-class (class (send action-spec :action_result))
action-feedback-class (class (send action-spec :action_feedback)))
(ros::advertise (format nil "~A/goal" name-space) action-goal-class 0)
(ros::advertise (format nil "~A/cancel" name-space) actionlib_msgs::GoalID 0)
(ros::advertise (format nil "~A/goal" name-space) action-goal-class 10)
(ros::advertise (format nil "~A/cancel" name-space) actionlib_msgs::GoalID 10)
(cond
(groupname
(ros::subscribe (format nil "~A/status" name-space)
actionlib_msgs::GoalStatusArray #'send self :goal-status-cb 0 :groupname groupname)
actionlib_msgs::GoalStatusArray #'send self :goal-status-cb 1 :groupname groupname)
(ros::subscribe (format nil "~A/result" name-space)
action-result-class #'send self :action-result-cb 0 :groupname groupname)
action-result-class #'send self :action-result-cb 1 :groupname groupname)
(ros::subscribe (format nil "~A/feedback" name-space)
action-feedback-class #'send self :action-feedback-cb 0 :groupname groupname))
action-feedback-class #'send self :action-feedback-cb 1 :groupname groupname))
(t
(ros::subscribe (format nil "~A/status" name-space)
actionlib_msgs::GoalStatusArray #'send self :goal-status-cb 0)
actionlib_msgs::GoalStatusArray #'send self :goal-status-cb 1)
(ros::subscribe (format nil "~A/result" name-space)
action-result-class #'send self :action-result-cb 0)
action-result-class #'send self :action-result-cb 1)
(ros::subscribe (format nil "~A/feedback" name-space)
action-feedback-class #'send self :action-feedback-cb 0)))
action-feedback-class #'send self :action-feedback-cb 1)))
(setq simple-state ros::*simple-goal-state-done*)
self)
(:wait-for-server
Expand Down Expand Up @@ -359,20 +359,20 @@
(setq action-goal-class (class (send action-spec :action_goal))
action-result-class (class (send action-spec :action_result))
action-feedback-class (class (send action-spec :action_feedback)))
(ros::advertise (format nil "~A/status" name-space) actionlib_msgs::GoalStatusArray)
(ros::advertise (format nil "~A/result" name-space) action-result-class)
(ros::advertise (format nil "~A/feedback" name-space) action-feedback-class)
(ros::advertise (format nil "~A/status" name-space) actionlib_msgs::GoalStatusArray 50)
(ros::advertise (format nil "~A/result" name-space) action-result-class 50)
(ros::advertise (format nil "~A/feedback" name-space) action-feedback-class 50)
(cond
(groupname
(ros::subscribe (format nil "~A/goal" name-space)
action-goal-class #'send self :goal-callback 0 :groupname groupname)
action-goal-class #'send self :goal-callback 50 :groupname groupname)
(ros::subscribe (format nil "~A/cancel" name-space)
actionlib_msgs::GoalID #'send self :cancel-callback 0 :groupname groupname))
actionlib_msgs::GoalID #'send self :cancel-callback 50 :groupname groupname))
(t
(ros::subscribe (format nil "~A/goal" name-space)
action-goal-class #'send self :goal-callback 0)
action-goal-class #'send self :goal-callback 50)
(ros::subscribe (format nil "~A/cancel" name-space)
actionlib_msgs::GoalID #'send self :cancel-callback 0)))
actionlib_msgs::GoalID #'send self :cancel-callback 50)))
;; need getparam for status_frequence, status_list_timeout
)
;;
Expand Down

0 comments on commit 87d0d62

Please sign in to comment.