Skip to content

Commit

Permalink
Rename tactile_merger -> contact_force_estimator
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Sep 23, 2022
1 parent 3cc8336 commit e5dcfec
Show file tree
Hide file tree
Showing 11 changed files with 35 additions and 36 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ This software package adds tactile messages, a tactile sensor description to URD
* [tactile_calibration](tactile_calibration)
* `tactile_state_calibrator`: maps raw tactile values to calibrated ones
* [urdf_tactile](urdf_tactile/README.md): extension to URDF to describe tactile sensors, requires modified [`urdf`](https://github.com/ubi-agni/urdf) and [`urdfdom`](https://github.com/ubi-agni/urdfdom) packages.
* [tactile_merger](tactile_merger): Map [`tactile_msgs/TactileState`](tactile_msgs/msg/TactileState.msg) onto [`tactile_msgs/TactileContacts`](tactile_msgs/msg/TactileContacts.msg), i.e. contact position, force, and normal, merging contact data of all taxels per link into a single wrench vector
* [contact_force_estimator](contact_force_estimator): Map [`tactile_msgs/TactileState`](tactile_msgs/msg/TactileState.msg) onto [`tactile_msgs/TactileContacts`](tactile_msgs/msg/TactileContacts.msg), i.e. contact position, force, and normal, aggregating contact data of all taxels per link into a single wrench vector.
* [tactile_pcl](tactile_pcl): Compute and publish Tactile Point Cloud data from [`tactile_msgs/TactileContacts`](tactile_msgs/msg/TactileState.msg).
* [rviz_tactile_plugins](rviz_tactile_plugins): rviz visualization tools for [raw tactile data](tactile_msgs/msg/TactileState.msg) and [contact information](tactile_msgs/msg/TactileContacts.msg).

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.1.3)
project(tactile_merger)
project(contact_force_estimator)

set(CMAKE_CXX_STANDARD 14)

Expand All @@ -23,15 +23,14 @@ include_directories(SYSTEM ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR})
# https://gitlab.kitware.com/cmake/community/-/wikis/doc/cmake/RPATH-handling
set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)


add_library(${PROJECT_NAME}
src/taxel.cpp
src/taxel_group.cpp
src/merger.cpp
src/contact_force_estimator.cpp
)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})

add_executable(${PROJECT_NAME}_node src/merger_node.cpp)
add_executable(${PROJECT_NAME}_node src/node.cpp)
target_link_libraries(${PROJECT_NAME}_node ${PROJECT_NAME})
set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME ${PROJECT_NAME})

Expand All @@ -44,5 +43,5 @@ install(TARGETS
)

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h")
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h")
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,11 @@

namespace tactile {

class Merger
class ContactForceEstimator
{
public:
Merger();
~Merger();
ContactForceEstimator();
~ContactForceEstimator();

void init(const std::string &param = "robot_description");

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<package format="3">
<name>tactile_merger</name>
<name>contact_force_estimator</name>
<version>0.1.0</version>
<description>merge raw tactile data into TactileContact msgs</description>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <tactile_merger/merger.h>
#include <contact_force_estimator/contact_force_estimator.h>
#include <tactile_msgs/TactileContacts.h>
#include <boost/thread/mutex.hpp>
#include <boost/thread/locks.hpp>
Expand All @@ -35,7 +35,7 @@

namespace tactile {

struct Merger::GroupData
struct ContactForceEstimator::GroupData
{
GroupData(const TaxelGroupPtr &group);

Expand All @@ -44,17 +44,17 @@ struct Merger::GroupData
ros::Time timestamp;
};

Merger::GroupData::GroupData(const TaxelGroupPtr &group) : group(group) {}
ContactForceEstimator::GroupData::GroupData(const TaxelGroupPtr &group) : group(group) {}

Merger::Merger() {}
Merger::~Merger()
ContactForceEstimator::ContactForceEstimator() {}
ContactForceEstimator::~ContactForceEstimator()
{
sensors_.clear();
groups_.clear();
parsers_.clear();
}

void Merger::init(const std::string &param)
void ContactForceEstimator::init(const std::string &param)
{
sensors_.clear();
groups_.clear();
Expand All @@ -73,14 +73,14 @@ void Merger::init(const std::string &param)
}
}

void Merger::reset()
void ContactForceEstimator::reset()
{
for (auto &group : groups_)
group.second->timestamp = ros::Time();
}

template <typename Iterator>
void Merger::update(const ros::Time &stamp, const std::string &channel, Iterator begin, Iterator end)
void ContactForceEstimator::update(const ros::Time &stamp, const std::string &channel, Iterator begin, Iterator end)
{
auto range = sensors_.equal_range(channel);
if (range.first == range.second) {
Expand All @@ -99,11 +99,11 @@ void Merger::update(const ros::Time &stamp, const std::string &channel, Iterator
}
}
}
template void Merger::update<std::vector<float>::const_iterator>(const ros::Time &stamp, const std::string &sensor_name,
std::vector<float>::const_iterator begin,
std::vector<float>::const_iterator end);
template void ContactForceEstimator::update<std::vector<float>::const_iterator>(
const ros::Time &stamp, const std::string &sensor_name, std::vector<float>::const_iterator begin,
std::vector<float>::const_iterator end);

tactile_msgs::TactileContacts Merger::getAllTaxelContacts()
tactile_msgs::TactileContacts ContactForceEstimator::getAllTaxelContacts()
{
static ros::Duration timeout(1);
ros::Time now = ros::Time::now();
Expand All @@ -125,7 +125,7 @@ tactile_msgs::TactileContacts Merger::getAllTaxelContacts()
return contacts;
}

tactile_msgs::TactileContacts Merger::getGroupAveragedContacts()
tactile_msgs::TactileContacts ContactForceEstimator::getGroupAveragedContacts()
{
static ros::Duration timeout(1);
ros::Time now = ros::Time::now();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,19 +26,19 @@
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <tactile_merger/merger.h>
#include <contact_force_estimator/contact_force_estimator.h>
#include <ros/ros.h>
#include <tactile_msgs/TactileContacts.h>
#include <tactile_msgs/TactileState.h>
#include <boost/bind.hpp>

static bool HAVE_NEW_DATA = false;

void message_handler(tactile::Merger &merger, const tactile_msgs::TactileStateConstPtr &msg)
void message_handler(tactile::ContactForceEstimator &estimator, const tactile_msgs::TactileStateConstPtr &msg)
{
HAVE_NEW_DATA = true;
for (auto it = msg->sensors.begin(), end = msg->sensors.end(); it != end; ++it) {
merger.update(msg->header.stamp, it->name, it->values.begin(), it->values.end());
estimator.update(msg->header.stamp, it->name, it->values.begin(), it->values.end());
}
}

Expand All @@ -48,13 +48,13 @@ int main(int argc, char *argv[])
ros::NodeHandle nh;
ros::NodeHandle nh_priv("~");

tactile::Merger merger;
merger.init();
tactile::ContactForceEstimator estimator;
estimator.init();

ros::Publisher pub = nh.advertise<tactile_msgs::TactileContacts>("tactile_contact_states", 5);

const boost::function<void(const tactile_msgs::TactileStateConstPtr &)> callback =
boost::bind(message_handler, boost::ref(merger), _1);
boost::bind(message_handler, boost::ref(estimator), _1);
ros::Subscriber sub = nh.subscribe("tactile_states", 1, callback);

ros::Time last_update;
Expand All @@ -65,17 +65,17 @@ int main(int argc, char *argv[])
ros::Time now = ros::Time::now();
if (now < last_update) {
ROS_WARN_STREAM("Detected jump back in time of " << (last_update - now).toSec() << "s. Resetting data.");
merger.reset();
estimator.reset();
HAVE_NEW_DATA = false;
}
last_update = now;

if (HAVE_NEW_DATA) {
HAVE_NEW_DATA = false;
if (no_clustering)
pub.publish(merger.getAllTaxelContacts());
pub.publish(estimator.getAllTaxelContacts());
else
pub.publish(merger.getGroupAveragedContacts());
pub.publish(estimator.getGroupAveragedContacts());
ros::spinOnce();
}
rate.sleep();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <tactile_merger/taxel.h>
#include <contact_force_estimator/taxel.h>

namespace tactile {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <tactile_merger/taxel_group.h>
#include <contact_force_estimator/taxel_group.h>

#include <urdf/sensor.h>
#include <ros/console.h>
Expand Down
2 changes: 1 addition & 1 deletion tactile_toolbox/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<exec_depend>tactile_state_publisher</exec_depend>
<exec_depend>tactile_state_calibrator</exec_depend>
<exec_depend>tactile_calibration_tools</exec_depend>
<exec_depend>tactile_merger</exec_depend>
<exec_depend>contact_force_estimator</exec_depend>
<exec_depend>tactile_pcl</exec_depend>
<exec_depend>rviz_tactile_plugins</exec_depend>

Expand Down

0 comments on commit e5dcfec

Please sign in to comment.