diff --git a/ambf_framework/afFramework.cpp b/ambf_framework/afFramework.cpp index 3b0e6bccb..ed4ebf009 100644 --- a/ambf_framework/afFramework.cpp +++ b/ambf_framework/afFramework.cpp @@ -5152,11 +5152,39 @@ afRigidBodyPtr afObjectManager::getRootRigidBody(afRigidBodyPtr a_bodyPtr){ return rootParentBody; } +/// +/// \brief afObjectManager::getJoint +/// \param a_name +/// \param suppress_warning +/// \return +/// afJointPtr afObjectManager::getJoint(string a_name, bool suppress_warning){ return (afJointPtr)getBaseObject(a_name, getJointMap(), suppress_warning); } +/// +/// \brief afObjectManager::getActuator +/// \param a_name +/// \param suppress_warning +/// \return +/// +afActuatorPtr afObjectManager::getActuator(string a_name, bool suppress_warning){ + return (afActuatorPtr)getBaseObject(a_name, getActuatorMap(), suppress_warning); +} + +/// +/// \brief afObjectManager::getSensor +/// \param a_name +/// \param suppress_warning +/// \return +/// +afSensorPtr afObjectManager::getSensor(string a_name, bool suppress_warning){ + return (afSensorPtr)getBaseObject(a_name, getSensorMap(), suppress_warning); + +} + + /// /// \brief afObjectManager::getSoftBody /// \param a_name diff --git a/ambf_framework/afFramework.h b/ambf_framework/afFramework.h index cae362503..e4273d213 100644 --- a/ambf_framework/afFramework.h +++ b/ambf_framework/afFramework.h @@ -783,9 +783,9 @@ class afObjectManager{ afJointPtr getJoint(string a_name, bool suppress_warning=false); - afActuatorPtr getActuator(string a_name); + afActuatorPtr getActuator(string a_name, bool suppress_warning=false); - afSensorPtr getSensor(string a_name); + afSensorPtr getSensor(string a_name, bool suppress_warning=false); afVehiclePtr getVehicle(string a_name, bool suppress_warning=false); diff --git a/ambf_plugins/core/ros_comm_plugin/ObjectCommPlugin.cpp b/ambf_plugins/core/ros_comm_plugin/ObjectCommPlugin.cpp index 95a4e3946..4be4a2611 100644 --- a/ambf_plugins/core/ros_comm_plugin/ObjectCommPlugin.cpp +++ b/ambf_plugins/core/ros_comm_plugin/ObjectCommPlugin.cpp @@ -75,6 +75,7 @@ int afObjectCommunicationPlugin::init(const afBaseObjectPtr a_afObjectPtr, const string objName = m_objectPtr->getName() + m_objectPtr->getGlobalRemapIdx(); string objNamespace = m_objectPtr->getNamespace(); + string objQualifiedIdentifier = m_objectPtr->getQualifiedIdentifier() + m_objectPtr->getGlobalRemapIdx(); int minFreq = m_objectPtr->getMinPublishFrequency(); int maxFreq = m_objectPtr->getMaxPublishFrequency(); double timeOut = 0.5; @@ -85,6 +86,7 @@ int afObjectCommunicationPlugin::init(const afBaseObjectPtr a_afObjectPtr, const case afType::ACTUATOR: { m_actuatorCommPtr.reset(new ambf_comm::Actuator(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_actuatorCommPtr->set_identifier(objQualifiedIdentifier); afActuatorPtr actPtr = (afActuatorPtr)m_objectPtr; switch (actPtr->m_actuatorType) { case afActuatorType::CONSTRAINT: @@ -100,30 +102,35 @@ int afObjectCommunicationPlugin::init(const afBaseObjectPtr a_afObjectPtr, const case afType::CAMERA: { m_cameraCommPtr.reset(new ambf_comm::Camera(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_cameraCommPtr->set_identifier(objQualifiedIdentifier); success = true; } break; case afType::LIGHT: { m_lightCommPtr.reset(new ambf_comm::Light(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_lightCommPtr->set_identifier(objQualifiedIdentifier); success = true; } break; case afType::OBJECT: { m_objectCommPtr.reset(new ambf_comm::Object(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_objectCommPtr->set_identifier(objQualifiedIdentifier); success = true; } break; case afType::RIGID_BODY: { m_rigidBodyCommPtr.reset(new ambf_comm::RigidBody(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_rigidBodyCommPtr->set_identifier(objQualifiedIdentifier); success = true; } break; case afType::SENSOR: { m_sensorCommPtr.reset(new ambf_comm::Sensor(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_sensorCommPtr->set_identifier(objQualifiedIdentifier); afSensorPtr senPtr = (afSensorPtr) m_objectPtr; switch (senPtr->m_sensorType) { case afSensorType::RAYTRACER: @@ -141,6 +148,7 @@ int afObjectCommunicationPlugin::init(const afBaseObjectPtr a_afObjectPtr, const case afType::VEHICLE: { m_vehicleCommPtr.reset(new ambf_comm::Vehicle(objName, objNamespace, minFreq, maxFreq, timeOut)); + m_actuatorCommPtr->set_identifier(objQualifiedIdentifier); success = true; } break; @@ -300,22 +308,35 @@ void afObjectCommunicationPlugin::actuatorFetchCommand(afActuatorPtr actPtr, dou // Constraint is active. Ignore request return; } - string body_name = cmd.body_name.data; - if (cmd.use_offset){ - // Offset of constraint (joint) in sensed body (child) - btTransform T_jINc; - T_jINc.setOrigin(btVector3(cmd.body_offset.position.x, - cmd.body_offset.position.y, - cmd.body_offset.position.z)); - - T_jINc.setRotation(btQuaternion(cmd.body_offset.orientation.x, - cmd.body_offset.orientation.y, - cmd.body_offset.orientation.z, - cmd.body_offset.orientation.w)); - castPtr->actuate(body_name, T_jINc); + else if (cmd.use_sensor_data){ + std::string sensorName = cmd.sensor_identifier.data; + afSensorPtr senPtr = actPtr->m_afWorld->getSensor(sensorName); + if (senPtr){ + castPtr->actuate(senPtr); + } + else{ + cerr << "ERROR! IN ACTUATOR CALLBACK " << castPtr->getName() << + ", REQUESTED SENSOR NAME " << sensorName << " NOT FOUND. IGNORING!" << endl; + } } else{ - castPtr->actuate(body_name); + string body_name = cmd.body_name.data; + if (cmd.use_offset){ + // Offset of constraint (joint) in sensed body (child) + btTransform T_jINc; + T_jINc.setOrigin(btVector3(cmd.body_offset.position.x, + cmd.body_offset.position.y, + cmd.body_offset.position.z)); + + T_jINc.setRotation(btQuaternion(cmd.body_offset.orientation.x, + cmd.body_offset.orientation.y, + cmd.body_offset.orientation.z, + cmd.body_offset.orientation.w)); + castPtr->actuate(body_name, T_jINc); + } + else{ + castPtr->actuate(body_name); + } } } else{ @@ -333,7 +354,6 @@ void afObjectCommunicationPlugin::actuatorUpdateState(afActuatorPtr actPtr, doub { m_actuatorCommPtr->m_writeMtx.lock(); setTimeStamps(m_objectPtr->m_afWorld->getWallTime(), m_objectPtr->m_afWorld->getSimulationTime(), m_objectPtr->getCurrentTimeStamp()); - m_actuatorCommPtr->set_name(actPtr->getName()); m_actuatorCommPtr->set_parent_name(actPtr->m_parentName); m_actuatorCommPtr->m_writeMtx.unlock(); m_actuatorCommPtr->enableComm(); @@ -809,7 +829,6 @@ void afObjectCommunicationPlugin::sensorUpdateState(afSensorPtr senPtr, double d { afRayTracerSensorPtr raySenPtr = (afRayTracerSensorPtr) senPtr; m_sensorCommPtr->set_count(raySenPtr->getCount()); - m_sensorCommPtr->set_name(raySenPtr->getName()); m_sensorCommPtr->set_parent_name(raySenPtr->m_parentName); m_sensorCommPtr->set_range(raySenPtr->m_range); cVector3d pos = raySenPtr->getLocalPos(); diff --git a/ambf_ros_modules/ambf_client/python/ambf_actuator.py b/ambf_ros_modules/ambf_client/python/ambf_actuator.py index e066ab245..cd2eb9379 100755 --- a/ambf_ros_modules/ambf_client/python/ambf_actuator.py +++ b/ambf_ros_modules/ambf_client/python/ambf_actuator.py @@ -74,8 +74,19 @@ def actuate(self, obj_name, pose=None): self._cmd.body_name.data = obj_name self._cmd.actuate = True + def actuate_from_sensor_data(self, sensor_identifer): + """ + :param sensor_name: + :return: + """ + self._cmd.use_sensor_data = True + self._cmd.sensor_identifier.data = sensor_identifer + self._cmd.actuate = True + def deactuate(self): """ :return: """ self._cmd.actuate = False + self._cmd.use_sensor_data = False + self._cmd.sensor_identifier.data = '' diff --git a/ambf_ros_modules/ambf_client/python/ambf_base_object.py b/ambf_ros_modules/ambf_client/python/ambf_base_object.py index ba842e71c..481d1e24f 100755 --- a/ambf_ros_modules/ambf_client/python/ambf_base_object.py +++ b/ambf_ros_modules/ambf_client/python/ambf_base_object.py @@ -172,6 +172,12 @@ def get_rot_command(self): else: return self._state.pose.orientation + def get_identifier(self): + """ + :return: + """ + return self._state.identifier.data + def get_name(self): """ Get the name of this object diff --git a/ambf_ros_modules/ambf_msgs/msg/ActuatorCmd.msg b/ambf_ros_modules/ambf_msgs/msg/ActuatorCmd.msg index 4c5812869..afd52e9ae 100644 --- a/ambf_ros_modules/ambf_msgs/msg/ActuatorCmd.msg +++ b/ambf_ros_modules/ambf_msgs/msg/ActuatorCmd.msg @@ -3,3 +3,5 @@ bool actuate std_msgs/String body_name bool use_offset geometry_msgs/Pose body_offset +bool use_sensor_data +std_msgs/String sensor_identifier diff --git a/ambf_ros_modules/ambf_msgs/msg/ActuatorState.msg b/ambf_ros_modules/ambf_msgs/msg/ActuatorState.msg index 1ef448e6a..57a5068fd 100644 --- a/ambf_ros_modules/ambf_msgs/msg/ActuatorState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/ActuatorState.msg @@ -2,6 +2,7 @@ Header header uint32 sim_step std_msgs/String type std_msgs/String parent_name +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/CameraState.msg b/ambf_ros_modules/ambf_msgs/msg/CameraState.msg index 76b5b6b91..beb803464 100644 --- a/ambf_ros_modules/ambf_msgs/msg/CameraState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/CameraState.msg @@ -1,6 +1,7 @@ Header header uint32 sim_step std_msgs/String parent_name +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/LightState.msg b/ambf_ros_modules/ambf_msgs/msg/LightState.msg index 76b5b6b91..beb803464 100644 --- a/ambf_ros_modules/ambf_msgs/msg/LightState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/LightState.msg @@ -1,6 +1,7 @@ Header header uint32 sim_step std_msgs/String parent_name +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/ObjectState.msg b/ambf_ros_modules/ambf_msgs/msg/ObjectState.msg index 85fdfabac..f78dce31f 100644 --- a/ambf_ros_modules/ambf_msgs/msg/ObjectState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/ObjectState.msg @@ -1,5 +1,6 @@ Header header uint32 sim_step +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/RigidBodyState.msg b/ambf_ros_modules/ambf_msgs/msg/RigidBodyState.msg index ef8fdb6b7..622e976a3 100644 --- a/ambf_ros_modules/ambf_msgs/msg/RigidBodyState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/RigidBodyState.msg @@ -1,5 +1,6 @@ Header header uint32 sim_step +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/SensorState.msg b/ambf_ros_modules/ambf_msgs/msg/SensorState.msg index 78381906a..322cf735e 100644 --- a/ambf_ros_modules/ambf_msgs/msg/SensorState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/SensorState.msg @@ -2,6 +2,7 @@ Header header uint32 sim_step std_msgs/String type std_msgs/String parent_name +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/SoftBodyState.msg b/ambf_ros_modules/ambf_msgs/msg/SoftBodyState.msg index 85fdfabac..f78dce31f 100644 --- a/ambf_ros_modules/ambf_msgs/msg/SoftBodyState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/SoftBodyState.msg @@ -1,5 +1,6 @@ Header header uint32 sim_step +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_msgs/msg/VehicleState.msg b/ambf_ros_modules/ambf_msgs/msg/VehicleState.msg index def25d043..8be9cd18c 100644 --- a/ambf_ros_modules/ambf_msgs/msg/VehicleState.msg +++ b/ambf_ros_modules/ambf_msgs/msg/VehicleState.msg @@ -1,5 +1,6 @@ Header header uint32 sim_step +std_msgs/String identifier std_msgs/String name float32 wall_time float32 sim_time diff --git a/ambf_ros_modules/ambf_server/include/ambf_server/RosComBase.h b/ambf_ros_modules/ambf_server/include/ambf_server/RosComBase.h index 994990725..0cf26b489 100644 --- a/ambf_ros_modules/ambf_server/include/ambf_server/RosComBase.h +++ b/ambf_ros_modules/ambf_server/include/ambf_server/RosComBase.h @@ -142,6 +142,10 @@ class RosComBase{ m_State.name.data = name; } + inline void set_identifier(std::string identifier){ + m_State.identifier.data = identifier; + } + inline void set_time_stamp(double a_sec){ m_State.header.stamp.fromSec(a_sec); } diff --git a/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp1.png b/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp1.png new file mode 100644 index 000000000..b11c1ea3c Binary files /dev/null and b/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp1.png differ diff --git a/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp2.png b/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp2.png new file mode 100644 index 000000000..7ae49e127 Binary files /dev/null and b/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp2.png differ diff --git a/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp3.png b/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp3.png new file mode 100644 index 000000000..72c55d74f Binary files /dev/null and b/ambf_ros_modules/examples/sensors_actuators_example/Images/sb_grasp3.png differ diff --git a/ambf_ros_modules/examples/sensors_actuators_example/README.md b/ambf_ros_modules/examples/sensors_actuators_example/README.md index 8b3d4fa43..68a899895 100644 --- a/ambf_ros_modules/examples/sensors_actuators_example/README.md +++ b/ambf_ros_modules/examples/sensors_actuators_example/README.md @@ -52,3 +52,32 @@ This is an example of what you should see: ### Note: If you accidentally drop or misplace the box, you can click the simulation window and hit `CRTL + R` to reset the object poses in the simulation. + +### SOFT-BODY GRASPING (Beta Feature): + +Run the simulation as follows: + +``` bash +cd /bin/lin-x86_64/ +./ambf_simulator --launch_file /ambf_ros_modules/examples/sensors_actuators_example/launch.yaml -l 0,1,2,3,4 +``` +The last two ADF files represent a textured ground and a softbody box. + +Similar to before, run the GUI with joint sliders and the sensing_and_grasping.py script. + +``` +cd /ambf_ros_modules/examples/sensors_actuators_example/ +python sensing_and_grasping.py +``` + +By moving the KUKA robot such that the visible sensors touch the softbody, one can press the grasp button (from sensing_and_grasping GUI) to grasp the softbody. Pressing the release button will release the softbody. + +This is what the demo should look like. + + + + + + + +Checkout the `sensing_and_grasping.py` script for understanding how to use the `constraint actuators` for grasping a softbody using the new beta API. diff --git a/ambf_ros_modules/examples/sensors_actuators_example/launch.yaml b/ambf_ros_modules/examples/sensors_actuators_example/launch.yaml index aadba0fea..ae778b091 100644 --- a/ambf_ros_modules/examples/sensors_actuators_example/launch.yaml +++ b/ambf_ros_modules/examples/sensors_actuators_example/launch.yaml @@ -7,3 +7,5 @@ multibody configs: - "../../../ambf_models/descriptions/multi-bodies/robots/blender-kuka-lbr-med.yaml" #0 - "./sensors_actuators.yaml" #1 - "./box.yaml" #2 + - "../../../ambf_models/descriptions/multi-bodies/environments/TexturedGround/env.yaml" #3 + - "../../../ambf_models/descriptions/multi-bodies/sb/magic_box.yaml" #4 diff --git a/ambf_ros_modules/examples/sensors_actuators_example/sensing_and_grasping.py b/ambf_ros_modules/examples/sensors_actuators_example/sensing_and_grasping.py index 72cb639a1..e89b97a33 100644 --- a/ambf_ros_modules/examples/sensors_actuators_example/sensing_and_grasping.py +++ b/ambf_ros_modules/examples/sensors_actuators_example/sensing_and_grasping.py @@ -1,4 +1,5 @@ from ambf_client import Client +import rospy import time import sys if sys.version_info[0] >= 3: @@ -6,7 +7,11 @@ else: from Tkinter import * -global sensor_array, actuator_array, sensor_triggered, actuator_activated, grasp + +sensor_obj = None +actuators = [] +actuators_activation_state = [] +grasp = False def grasp_button_cb(): @@ -21,40 +26,56 @@ def release_button_cb(): print('RELEASE REQUESTED') -def grasp_object(grasp): - global sensor_array, actuator_array, sensor_triggered, actuator_activated +def print_sensors_state(sensor_obj): + print('Sensor Array Triggers: [', end=' ') + for i in range(sensor_obj.get_count()): + print(sensor_obj.is_triggered(i), end=' ') - sensor_count = sensor_array.get_count() + print(']') - for i in range(sensor_count): - if sensor_array.is_triggered(i): - sensor_triggered[i] = True - else: - sensor_triggered[i] = False - print('Sensor Array Triggers: ', sensor_triggered) +def grasp_object(grasp): + sensor_count = sensor_obj.get_count() if grasp: for i in range(sensor_count): - if sensor_triggered[i] and actuator_activated[i] is False: - obj_name = sensor_array.get_sensed_object(i) + if sensor_obj.is_triggered(i) and actuators_activation_state[i] is False: + obj_name = sensor_obj.get_sensed_object(i) print('Grasping ', obj_name, ' via actuator ', i) - actuator_array[i].actuate(obj_name) - actuator_activated[i] = True + actuators[i].actuate(obj_name) + actuators_activation_state[i] = True + else: + for i in range(sensor_count): + actuators[i].deactuate() + if actuators_activation_state[i] is True: + print('Releasing object from actuator ', i) + actuators_activation_state[i] = False + + +def grasp_object_via_sensor_name(grasp): + global sensor_obj + sensor_count = sensor_obj.get_count() + + if grasp: + for i in range(sensor_count): + if sensor_obj.is_triggered(i) and actuators_activation_state[i] is False: + actuators[i].actuate_from_sensor_data(sensor_obj.get_identifier()) + actuators_activation_state[i] = True + print('Actuating actuator ', i, 'named: ', actuators[i].get_name()) else: for i in range(sensor_count): - actuator_array[i].deactuate() - if actuator_activated[i] is True: + actuators[i].deactuate() + if actuators_activation_state[i] is True: print('Releasing object from actuator ', i) - actuator_activated[i] = False + actuators_activation_state[i] = False def main(): - global sensor_array, actuator_array, sensor_triggered, actuator_activated, grasp + global sensor_obj, actuators, actuators_activation_state, grasp c = Client('sensor_actuators_example') c.connect() # We have a sensor array (4 individual sensing elements) - sensor_array = c.get_obj_handle('tip_sensor_array') + sensor_obj = c.get_obj_handle('tip_sensor_array') # We have four corresponding constraint actuators, that we are going to actuate based on the trigger events from the # above sensors. Note that there is not explicit relation between a sensor and an actuator, it is we who are @@ -64,15 +85,14 @@ def main(): actuator2 = c.get_obj_handle('tip_actuator2') actuator3 = c.get_obj_handle('tip_actuator3') - actuator_array = [actuator0, actuator1, actuator2, actuator3] - sensor_triggered = [False, False, False, False] - actuator_activated = [False, False, False, False] + actuators = [actuator0, actuator1, actuator2, actuator3] + actuators_activation_state = [False, False, False, False] grasp = False time.sleep(1.0) tk = Tk() - tk.title("Attache Needle") + tk.title("Sensing and Grasping Example") tk.geometry("250x150") grasp_button = Button( tk, text="Grasp", command=grasp_button_cb, height=3, width=50, bg="red") @@ -81,11 +101,17 @@ def main(): grasp_button.pack() release_button.pack() - while True: + counter = 0 + while not rospy.is_shutdown(): try: tk.update() - grasp_object(grasp) + if not (counter % 50): + print_sensors_state(sensor_obj) + counter = 0 + # grasp_object(grasp) + grasp_object_via_sensor_name(grasp) time.sleep(0.02) + counter = counter + 1 except KeyboardInterrupt: print('Exiting Program') break