diff --git a/bindings/python/examples/LittleDog_id.py b/bindings/python/examples/LittleDog_id.py index 585e123a..d8edd015 100644 --- a/bindings/python/examples/LittleDog_id.py +++ b/bindings/python/examples/LittleDog_id.py @@ -2,25 +2,28 @@ import rospkg from xbot2_interface import pyxbot2_interface as xbi -from pyopensot.tasks.velocity import Postural, Cartesian, Manipulability, MinimumEffort -from pyopensot.constraints.velocity import JointLimits, VelocityLimits +from pyopensot.tasks.acceleration import Cartesian, CoM, DynamicFeasibility +from pyopensot.constraints.acceleration import JointLimits, VelocityLimits +from pyopensot.constraints.force import FrictionCone import pyopensot as pysot import numpy as np import rospy from sensor_msgs.msg import JointState +from geometry_msgs.msg import TransformStamped, WrenchStamped +import tf import subprocess # Check for franka_cartesio_condif package try: package_path = rospkg.RosPack().get_path('LittleDog') except: - print("To run this example is needed the anymal_c_simple_description package that can be download here: https://github.com/ANYbotics/anymal_c_simple_description") + print("To run this example is needed the anymal_c_simple_description package that can be download here: https://github.com/EnricoMingo/LittleDog") launch_path = package_path + "/launch/LittleDog.launch" print(launch_path) roslaunch = subprocess.Popen(['roslaunch', launch_path], stdout=subprocess.PIPE, shell=False) -#rviz_file_path = os.getcwd() + "/panda_ik.rviz" -#rviz = subprocess.Popen(['rviz', '-d', f'{rviz_file_path}'], stdout=subprocess.PIPE, shell=False) +rviz_file_path = os.getcwd() + "/LittleDog_id.rviz" +rviz = subprocess.Popen(['rviz', '-d', f'{rviz_file_path}'], stdout=subprocess.PIPE, shell=False) # Initiliaze node and wait for robot_description parameter rospy.init_node("LittleDog_id", disable_signals=True) @@ -30,5 +33,126 @@ # Get robot description parameter and initialize model interface (with Pinocchio) urdf = rospy.get_param('/robot_description') model = xbi.ModelInterface2(urdf) +qmin, qmax = model.getJointLimits() +dqmax = model.getVelocityLimits() +q = [0., 0., 0., 0., 0., 0., 1., + 0., -0.7, 1.4, 0., -0.7, 1.4, 0., 0.7, -1.4, 0., 0.7, -1.4] +dq = np.zeros(model.nv) +model.setJointPosition(q) +model.setJointVelocity(dq) +model.update() + +dt = 1./1000. + +# Instantiate Variables: qddot and contact forces (3 per contact) +contact_frames = ["front_left_foot_center", "front_right_foot_center", "back_left_foot_center", "back_right_foot_center"] +variables_vec = dict() +variables_vec["qddot"] = model.nv +for contact_frame in contact_frames: + variables_vec[contact_frame] = 3 +variables = pysot.OptvarHelper(variables_vec) + +# Creates tasks cand constraints +com = CoM(model, variables.getVariable("qddot")) +com.setLambda(1.) +com_ref, vel_ref, acc_ref = com.getReference() +com0 = com_ref.copy() + +base = Cartesian("base", model, "world", "body", variables.getVariable("qddot")) +base.setLambda(1.) + +contact_tasks = list() +for contact_frame in contact_frames: + contact_tasks.append(Cartesian(contact_frame + "_kin", model, contact_frame, "world", variables.getVariable("qddot"))) + +stack = 0.1*com + 0.1*(base%[3, 4, 5]) +force_variables = list() +for i in range(len(contact_frames)): + stack = stack + 10.*(contact_tasks[i]%[0, 1, 2]) + force_variables.append(variables.getVariable(contact_frames[i])) + +# Creates the stack. +# Notice: we do not need to keep track of the DynamicFeasibility constraint so it is created when added into the stack. +# The same can be done with other constraints such as Joint Limits and Velocity Limits +stack = pysot.AutoStack(stack) << DynamicFeasibility("floating_base_dynamics", model, variables.getVariable("qddot"), force_variables, contact_frames) +stack = stack << JointLimits(model, variables.getVariable("qddot"), qmax, qmin, 10.*dqmax, dt) +stack = stack << VelocityLimits(model, variables.getVariable("qddot"), dqmax, dt) +for i in range(len(contact_frames)): + T = model.getPose(contact_frames[i]) + mu = (T.linear, 0.8) # rotation is world to contact + stack = stack << FrictionCone(contact_frames[i], variables.getVariable(contact_frames[i]), model, mu) + +# Creates the solver +solver = pysot.iHQP(stack) + +# ID loop: we publish also joint position, floating-base pose and contact forces +rate = rospy.Rate(1./dt) +pub = rospy.Publisher('joint_states', JointState, queue_size=10) +msg = JointState() +msg.name = model.getJointNames()[1::] +br = tf.TransformBroadcaster() +w_T_b = TransformStamped() +w_T_b.header.frame_id = "world" +w_T_b.child_frame_id = "body" +force_msg = list() +fpubs = list() +for contact_frame in contact_frames: + force_msg.append(WrenchStamped()) + force_msg[-1].header.frame_id = contact_frame + force_msg[-1].wrench.torque.x = force_msg[-1].wrench.torque.y = force_msg[-1].wrench.torque.z = 0. + fpubs.append(rospy.Publisher(contact_frame, WrenchStamped, queue_size=10)) + +t = 0. +alpha = 0.05 +while not rospy.is_shutdown(): + # Update actual position in the model + model.setJointPosition(q) + model.setJointVelocity(dq) + model.update() + + # Compute new reference for CoM task + com_ref[2] = com0[2] + alpha * np.sin(3.1415 * t) + com_ref[1] = com0[1] + alpha * np.cos(3.1415 * t) + t = t + dt + com.setReference(com_ref) + + # Update Stack + stack.update() + + # Solve + x = solver.solve() + ddq = variables.getVariable("qddot").getValue(x) # from variables vector we retrieve the joint accelerations + q = model.sum(q, dq*dt + 0.5 * ddq * dt * dt) # we use the model sum to account for the floating-base + dq += ddq*dt + + # Publish joint states + msg.position = q[7::] + msg.header.stamp = rospy.get_rostime() + + w_T_b.header.stamp = msg.header.stamp + w_T_b.transform.translation.x = q[0] + w_T_b.transform.translation.y = q[1] + w_T_b.transform.translation.z = q[2] + w_T_b.transform.rotation.x = q[3] + w_T_b.transform.rotation.y = q[4] + w_T_b.transform.rotation.z = q[5] + w_T_b.transform.rotation.w = q[6] + + for i in range(len(contact_frames)): + T = model.getPose(contact_frames[i]) + force_msg[i].header.stamp = msg.header.stamp + f_local = T.linear.transpose() @ variables.getVariable(contact_frames[i]).getValue(x) # here we compute the value of the contact forces in local frame from world frame + force_msg[i].wrench.force.x = f_local[0] + force_msg[i].wrench.force.y = f_local[1] + force_msg[i].wrench.force.z = f_local[2] + fpubs[i].publish(force_msg[i]) + + pub.publish(msg) + br.sendTransformMessage(w_T_b) + + rate.sleep() + +roslaunch.kill() +rviz.kill() \ No newline at end of file diff --git a/bindings/python/examples/LittleDog_id.rviz b/bindings/python/examples/LittleDog_id.rviz new file mode 100644 index 00000000..7b6ef6b5 --- /dev/null +++ b/bindings/python/examples/LittleDog_id.rviz @@ -0,0 +1,312 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /TF1/Frames1 + Splitter Ratio: 0.5 + Tree Height: 746 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/InteractiveMarkers + Enable Transparency: true + Enabled: true + Name: InteractiveMarkers + Show Axes: false + Show Descriptions: true + Show Visual Aids: false + Update Topic: /left_foot_cartesian_marker_server/update + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: true + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + back_left_foot_center: + Alpha: 1 + Show Axes: false + Show Trail: false + back_left_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + back_left_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + back_left_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + back_right_foot_center: + Alpha: 1 + Show Axes: false + Show Trail: false + back_right_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + back_right_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + back_right_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + body: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_left_foot_center: + Alpha: 1 + Show Axes: false + Show Trail: false + front_left_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + front_left_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_left_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_right_foot_center: + Alpha: 1 + Show Axes: false + Show Trail: false + front_right_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + front_right_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_right_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + world: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /visualization_marker + Name: Marker + Namespaces: + {} + Queue Size: 100 + Value: true + - Class: rviz/TF + Enabled: false + Filter (blacklist): "" + Filter (whitelist): "" + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Alpha: 1 + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 1 + Arrow Width: 0.20000000298023224 + Class: rviz/WrenchStamped + Enabled: true + Force Arrow Scale: 0.07999999821186066 + Force Color: 204; 51; 51 + Hide Small Values: true + History Length: 1 + Name: WrenchStamped + Queue Size: 10 + Topic: /back_left_foot_center + Torque Arrow Scale: 0 + Torque Color: 204; 204; 51 + Unreliable: false + Value: true + - Alpha: 1 + Arrow Width: 0.20000000298023224 + Class: rviz/WrenchStamped + Enabled: true + Force Arrow Scale: 0.07999999821186066 + Force Color: 204; 51; 51 + Hide Small Values: true + History Length: 1 + Name: WrenchStamped + Queue Size: 10 + Topic: /back_right_foot_center + Torque Arrow Scale: 0 + Torque Color: 204; 204; 51 + Unreliable: false + Value: true + - Alpha: 1 + Arrow Width: 0.20000000298023224 + Class: rviz/WrenchStamped + Enabled: true + Force Arrow Scale: 0.07999999821186066 + Force Color: 204; 51; 51 + Hide Small Values: true + History Length: 1 + Name: WrenchStamped + Queue Size: 10 + Topic: /front_left_foot_center + Torque Arrow Scale: 0 + Torque Color: 204; 204; 51 + Unreliable: false + Value: true + - Alpha: 1 + Arrow Width: 0.20000000298023224 + Class: rviz/WrenchStamped + Enabled: true + Force Arrow Scale: 0.07999999821186066 + Force Color: 204; 51; 51 + Hide Small Values: true + History Length: 1 + Name: WrenchStamped + Queue Size: 10 + Topic: /front_right_foot_center + Torque Arrow Scale: 0 + Torque Color: 204; 204; 51 + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 1.1156281232833862 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -0.022256191819906235 + Y: -0.047653235495090485 + Z: 0.17879575490951538 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -0.08020128309726715 + Target Frame: + Yaw: 0.6871967315673828 + Saved: ~ +Window Geometry: + Displays: + collapsed: true + Height: 1043 + Hide Left Dock: true + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000375fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730200000780000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d00000375000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000007380000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1848 + X: 72 + Y: 699 diff --git a/bindings/python/variables.hpp b/bindings/python/variables.hpp index ace00abe..020b0779 100644 --- a/bindings/python/variables.hpp +++ b/bindings/python/variables.hpp @@ -79,6 +79,13 @@ class OptvarHelperWrapper std::shared_ptr _optvar; }; +Eigen::VectorXd get_value(const AffineHelper& var, const Eigen::VectorXd& x) +{ + Eigen::VectorXd val; + var.getValue(x, val); + return val; +} + void pyAffineHelper(py::module& m, const std::string& className) { py::class_(m, className.c_str()) .def(py::init<>()) @@ -94,6 +101,7 @@ void pyAffineHelper(py::module& m, const std::string& className) { .def("setZero", py::overload_cast<>(&AffineHelper::setZero)) .def("setZero", py::overload_cast(&AffineHelper::setZero)) .def("update", &AffineHelper::update) + .def("getValue", get_value) .def("__sub__", [](const AffineHelper &a, const AffineHelper &b) { return diff(a, b); }) .def("__add__", [](const AffineHelper &a, const AffineHelper &b) { return sum(a, b); }) .def("__add__", [](const AffineHelper &a, const Eigen::VectorXd &v) { return sum(a, v); })