Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[rtm-ros-robot-interface.l] add start/stop-auto-balancer-odom-safe #1102

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 26 additions & 0 deletions hrpsys_ros_bridge/euslisp/rtm-ros-robot-interface.l
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
(ros::subscribe (format nil "/~A_contact_states" x) hrpsys_ros_bridge::ContactStatesStamped
#'send self :rtmros-contact-states-callback (read-from-string (format nil ":~A-contact-states" x)) :groupname groupname))
'(ref act))
(ros::subscribe "/odom" nav_msgs::Odometry
#'send self :rtmros-abc-odom-callback :groupname groupname)
))
(:rtmros-motor-states-callback
(msg)
Expand Down Expand Up @@ -77,6 +79,14 @@
(ref-act msg)
(let ((ss (send-all (send msg :states) :state :state)))
(send self :set-robot-state1 ref-act ss)))
(:rtmros-abc-odom-callback
(msg)
(let ((parsed
(list
(cons :stamp (send msg :header :stamp))
(cons :pose (ros::tf-pose->coords (send msg :pose :pose)))
(cons :twist (ros::tf-twist->coords (send msg :twist :twist))))))
(send self :set-robot-state1 :abc-odom parsed)))
(:tmp-force-moment-vector-for-limb
(f/m fsensor-name &optional (topic-name-prefix nil)) ;; topic-name-prefix is "off" or "reference"
(let ((key-name (if topic-name-prefix
Expand Down Expand Up @@ -2001,6 +2011,22 @@
(dolist (limb ic-limbs)
(send self :wait-impedance-controller-transition limb))
)
(:start-auto-balancer-odom-safe
(&rest args)
"Start AutoBalancer while keeping continuity of odometry
Foot-mid-coords have to be horizontal."
(send* self :start-auto-balancer args))
(:stop-auto-balancer-odom-safe
()
"Stop AutoBalancer while keeping continuity of odometry
You have to stop ImpedanceController and Stabilizer in advance"
(send self :angle-vector-sequence-full
(list (map float-vector #'rad2deg (send (send (send self :robothardwareservice_getStatus2) :rs) :command)))
(list 1) ;; This value have to be equal to or smaller than the control period of hrpsys
:root-coords (list (send self :state :abc-odom :pose)))
(send self :wait-interpolation-seq)
(send self :stop-auto-balancer)
)
)

;; ReferenceForceUpdater
Expand Down