|
From: <mee...@us...> - 2009-09-04 01:07:09
|
Revision: 23803
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23803&view=rev
Author: meeussen
Date: 2009-09-04 01:06:49 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
add new stats about joints, add controller state to mechanism state to replace the diagnostics that are not realtime safe. Remove hardware interface as much as possible from components
Modified Paths:
--------------
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/include/pr2_mechanism_control/mechanism_control.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/src/mechanism_control.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/joint.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/robot.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/joint.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/robot.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/JointState.msg
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/MechanismState.msg
pkg/trunk/stacks/pr2_simulator/pr2_gazebo_plugins/src/gazebo_mechanism_control.cpp
Added Paths:
-----------
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/ControllerState.msg
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/include/pr2_mechanism_control/mechanism_control.h
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/include/pr2_mechanism_control/mechanism_control.h 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/include/pr2_mechanism_control/mechanism_control.h 2009-09-04 01:06:49 UTC (rev 23803)
@@ -79,7 +79,6 @@
pr2_mechanism::Robot model_;
pr2_mechanism::RobotState *state_;
- HardwareInterface *hw_;
private:
void getControllerNames(std::vector<std::string> &v);
@@ -106,12 +105,13 @@
// for publishing constroller state/diagnostics
void publishDiagnostics();
- void publishState();
+ void publishJointState();
+ void publishMechanismState();
realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticArray> pub_diagnostics_;
realtime_tools::RealtimePublisher<sensor_msgs::JointState> pub_joint_state_;
realtime_tools::RealtimePublisher<pr2_mechanism_msgs::MechanismState> pub_mech_state_;
- double publish_period_state_, last_published_state_;
- double publish_period_diagnostics_, last_published_diagnostics_;
+ ros::Duration publish_period_joint_state_, publish_period_mechanism_state_, publish_period_diagnostics_;
+ ros::Time last_published_joint_state_, last_published_mechanism_state_, last_published_diagnostics_;
// services to work with controllers
bool listControllerTypesSrv(pr2_mechanism_msgs::ListControllerTypes::Request &req,
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/src/mechanism_control.cpp 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/src/mechanism_control.cpp 2009-09-04 01:06:49 UTC (rev 23803)
@@ -44,7 +44,7 @@
MechanismControl::MechanismControl(HardwareInterface *hw) :
model_(hw),
- state_(NULL), hw_(hw),
+ state_(NULL),
controller_loader_("pr2_controller_interface", "controller::Controller"),
start_request_(0),
stop_request_(0),
@@ -55,8 +55,9 @@
pub_diagnostics_(node_, "/diagnostics", 1),
pub_joint_state_(node_, "joint_states", 1),
pub_mech_state_(node_, "mechanism_state", 1),
- last_published_state_(ros::Time::now().toSec()),
- last_published_diagnostics_(ros::Time::now().toSec())
+ last_published_joint_state_(ros::Time::now()),
+ last_published_mechanism_state_(ros::Time::now()),
+ last_published_diagnostics_(ros::Time::now())
{}
MechanismControl::~MechanismControl()
@@ -69,10 +70,11 @@
bool MechanismControl::initXml(TiXmlElement* config)
{
model_.initXml(config);
- state_ = new RobotState(&model_, hw_);
+ state_ = new RobotState(&model_);
// pre-allocate for realtime publishing
- pub_mech_state_.msg_.set_actuator_states_size(hw_->actuators_.size());
+ pub_mech_state_.msg_.set_controller_states_size(0);
+ pub_mech_state_.msg_.set_actuator_states_size(model_.actuators_.size());
int joints_size = 0;
for (unsigned int i = 0; i < model_.joints_.size(); ++i)
{
@@ -86,6 +88,7 @@
pub_joint_state_.msg_.set_velocity_size(joints_size);
pub_joint_state_.msg_.set_effort_size(joints_size);
+
// Advertise services
srv_list_controllers_ = node_.advertiseService("list_controllers", &MechanismControl::listControllersSrv, this);
srv_list_controller_types_ = node_.advertiseService("list_controller_types", &MechanismControl::listControllerTypesSrv, this);
@@ -94,11 +97,13 @@
srv_switch_controller_ = node_.advertiseService("switch_controller", &MechanismControl::switchControllerSrv, this);
// get the publish rate for mechanism state and diagnostics
- double publish_rate_state, publish_rate_diagnostics;
- node_.param("~publish_rate_mechanism_state", publish_rate_state, 100.0);
+ double publish_rate_joint_state, publish_rate_mechanism_state, publish_rate_diagnostics;
+ node_.param("~publish_rate_mechanism_state", publish_rate_mechanism_state, 1.0);
+ node_.param("~publish_rate_joint_state", publish_rate_joint_state, 100.0);
node_.param("~publish_rate_diagnostics", publish_rate_diagnostics, 1.0);
- publish_period_state_ = 1.0/fmax(0.000001, publish_rate_state);
- publish_period_diagnostics_ = 1.0/fmax(0.000001, publish_rate_diagnostics);
+ publish_period_mechanism_state_ = Duration(1.0/fmax(0.000001, publish_rate_mechanism_state));
+ publish_period_joint_state_ = Duration(1.0/fmax(0.000001, publish_rate_joint_state));
+ publish_period_diagnostics_ = Duration(1.0/fmax(0.000001, publish_rate_diagnostics));
return true;
}
@@ -114,32 +119,33 @@
std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
std::vector<size_t> &scheduling = controllers_scheduling_[used_by_realtime_];
- double start = ros::Time::now().toSec();
+ ros::Time start = ros::Time::now();
state_->propagateState();
state_->zeroCommands();
- double start_update = ros::Time::now().toSec();
- pre_update_stats_.acc(start_update - start);
+ ros::Time start_update = ros::Time::now();
+ pre_update_stats_.acc((start_update - start).toSec());
// Update all controllers in scheduling order
for (size_t i=0; i<controllers.size(); i++){
- double start = ros::Time::now().toSec();
+ ros::Time start = ros::Time::now();
controllers[scheduling[i]].c->updateRequest();
- double end = ros::Time::now().toSec();
- controllers[scheduling[i]].stats->acc(end - start);
+ ros::Time end = ros::Time::now();
+ controllers[scheduling[i]].stats->acc((end - start).toSec());
}
- double end_update = ros::Time::now().toSec();
- update_stats_.acc(end_update - start_update);
+ ros::Time end_update = ros::Time::now();
+ update_stats_.acc((end_update - start_update).toSec());
state_->enforceSafety();
state_->propagateEffort();
- double end = ros::Time::now().toSec();
- post_update_stats_.acc(end - end_update);
+ ros::Time end = ros::Time::now();
+ post_update_stats_.acc((end - end_update).toSec());
// publish diagnostics and state
+ publishMechanismState();
+ publishJointState();
publishDiagnostics();
- publishState();
- // there are controllers to atomically start/stop
+ // there are controllers to start/stop
if (please_switch_)
{
// try to start controllers
@@ -285,6 +291,13 @@
return false;
}
+ // Resize controller state vector
+ pub_mech_state_.lock();
+ pub_mech_state_.msg_.set_controller_states_size(to.size());
+ for (size_t i=0; i<to.size(); i++)
+ pub_mech_state_.msg_.controller_states[i].name = to[i].name;
+ pub_mech_state_.unlock();
+
// Success! Swaps in the new set of controllers.
int former_current_controllers_list_ = current_controllers_list_;
current_controllers_list_ = free_controllers_list;
@@ -370,6 +383,13 @@
usleep(200);
from.clear();
+ // Resize controller state vector
+ pub_mech_state_.lock();
+ pub_mech_state_.msg_.set_controller_states_size(to.size());
+ for (size_t i=0; i<to.size(); i++)
+ pub_mech_state_.msg_.controller_states[i].name = to[i].name;
+ pub_mech_state_.unlock();
+
ROS_DEBUG("Successfully killed controller '%s'", name.c_str());
return true;
}
@@ -436,11 +456,12 @@
void MechanismControl::publishDiagnostics()
{
- if (round ((ros::Time::now().toSec() - last_published_diagnostics_ - publish_period_diagnostics_)/ (0.000001)) >= 0)
+ ros::Time now = ros::Time::now();
+ if (now > last_published_diagnostics_ + publish_period_diagnostics_)
{
- last_published_diagnostics_ = ros::Time::now().toSec();
if (pub_diagnostics_.trylock())
{
+ last_published_diagnostics_ = now;
std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
int active = 0;
TimeStatistics blank_statistics;
@@ -502,13 +523,49 @@
}
-void MechanismControl::publishState()
+void MechanismControl::publishJointState()
{
- if (round ((ros::Time::now().toSec() - last_published_state_ - publish_period_state_)/ (0.000001)) >= 0)
+ ros::Time now = ros::Time::now();
+ if (now > last_published_joint_state_ + publish_period_joint_state_)
{
- last_published_state_ = ros::Time::now().toSec();
+ if (pub_joint_state_.trylock())
+ {
+ last_published_joint_state_ = now;
+ unsigned int j = 0;
+ for (unsigned int i = 0; i < model_.joints_.size(); ++i)
+ {
+ int type = state_->joint_states_[i].joint_->type_;
+ if (type == urdf::Joint::REVOLUTE || type == urdf::Joint::CONTINUOUS || type == urdf::Joint::PRISMATIC)
+ {
+ assert(j < pub_joint_state_.msg_.get_name_size());
+ assert(j < pub_joint_state_.msg_.get_position_size());
+ assert(j < pub_joint_state_.msg_.get_velocity_size());
+ assert(j < pub_joint_state_.msg_.get_effort_size());
+ pr2_mechanism::JointState *in = &state_->joint_states_[i];
+ pub_joint_state_.msg_.name[j] = model_.joints_[i]->name_;
+ pub_joint_state_.msg_.position[j] = in->position_;
+ pub_joint_state_.msg_.velocity[j] = in->velocity_;
+ pub_joint_state_.msg_.effort[j] = in->applied_effort_;
+
+ j++;
+ }
+ }
+ pub_joint_state_.msg_.header.stamp = ros::Time::now();
+ pub_joint_state_.unlockAndPublish();
+ }
+ }
+}
+
+
+void MechanismControl::publishMechanismState()
+{
+ ros::Time now = ros::Time::now();
+ if (now > last_published_mechanism_state_ + publish_period_mechanism_state_)
+ {
if (pub_mech_state_.trylock())
{
+ last_published_mechanism_state_ = now;
+ // joint state
unsigned int j = 0;
for (unsigned int i = 0; i < model_.joints_.size(); ++i)
{
@@ -524,15 +581,23 @@
out->applied_effort = in->applied_effort_;
out->commanded_effort = in->commanded_effort_;
out->is_calibrated = in->calibrated_;
+ out->saturated = in->joint_statistics_.saturated_;
+ out->odometer = in->joint_statistics_.odometer_;
+ out->min_position = in->joint_statistics_.min_position_;
+ out->max_position = in->joint_statistics_.max_position_;
+ out->max_abs_velocity = in->joint_statistics_.max_abs_velocity_;
+ out->max_abs_effort = in->joint_statistics_.max_abs_effort_;
+ in->joint_statistics_.reset();
j++;
}
}
- for (unsigned int i = 0; i < hw_->actuators_.size(); ++i)
+ // actuator state
+ for (unsigned int i = 0; i < model_.actuators_.size(); ++i)
{
pr2_mechanism_msgs::ActuatorState *out = &pub_mech_state_.msg_.actuator_states[i];
- ActuatorState *in = &hw_->actuators_[i]->state_;
- out->name = hw_->actuators_[i]->name_;
+ ActuatorState *in = &model_.actuators_[i]->state_;
+ out->name = model_.actuators_[i]->name_;
out->encoder_count = in->encoder_count_;
out->position = in->position_;
out->timestamp = in->timestamp_;
@@ -555,41 +620,27 @@
out->motor_voltage = in->motor_voltage_;
out->num_encoder_errors = in->num_encoder_errors_;
}
- pub_mech_state_.msg_.header.stamp = ros::Time::now();
- pub_mech_state_.msg_.time = ros::Time::now().toSec();
- pub_mech_state_.unlockAndPublish();
- }
-
- if (pub_joint_state_.trylock())
- {
- unsigned int j = 0;
- for (unsigned int i = 0; i < model_.joints_.size(); ++i)
+ // controller state
+ std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
+ for (unsigned int i = 0; i < controllers.size(); ++i)
{
- int type = state_->joint_states_[i].joint_->type_;
- if (type == urdf::Joint::REVOLUTE || type == urdf::Joint::CONTINUOUS || type == urdf::Joint::PRISMATIC)
- {
- assert(j < pub_joint_state_.msg_.get_name_size());
- assert(j < pub_joint_state_.msg_.get_position_size());
- assert(j < pub_joint_state_.msg_.get_velocity_size());
- assert(j < pub_joint_state_.msg_.get_effort_size());
- pr2_mechanism::JointState *in = &state_->joint_states_[i];
- pub_joint_state_.msg_.name[j] = model_.joints_[i]->name_;
- pub_joint_state_.msg_.position[j] = in->position_;
- pub_joint_state_.msg_.velocity[j] = in->velocity_;
- pub_joint_state_.msg_.effort[j] = in->applied_effort_;
-
- j++;
- }
+ pr2_mechanism_msgs::ControllerState *out = &pub_mech_state_.msg_.controller_states[i];
+ out->running = controllers[i].c->isRunning();
+ out->max_time = max(controllers[i].stats->acc);
+ out->mean_time = mean(controllers[i].stats->acc);
+ out->variance_time = sqrt(variance(controllers[i].stats->acc));
}
- pub_joint_state_.msg_.header.stamp = ros::Time::now();
+ pub_mech_state_.msg_.header.stamp = ros::Time::now();
- pub_joint_state_.unlockAndPublish();
+ pub_mech_state_.unlockAndPublish();
}
}
}
+
+
bool MechanismControl::listControllerTypesSrv(
pr2_mechanism_msgs::ListControllerTypes::Request &req,
pr2_mechanism_msgs::ListControllerTypes::Response &resp)
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/joint.h
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/joint.h 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/joint.h 2009-09-04 01:06:49 UTC (rev 23803)
@@ -85,6 +85,29 @@
};
+
+class JointStatistics
+{
+ public:
+ JointStatistics():odometer_(0.0), max_abs_velocity_(0.0), max_abs_effort_(0.0),
+ saturated_(false), initialized_(false){}
+
+ void update(JointState* s);
+ void reset();
+
+ double odometer_;
+ double min_position_, max_position_;
+ double max_abs_velocity_;
+ double max_abs_effort_;
+ bool saturated_;
+
+ private:
+ bool initialized_;
+ double old_position_;
+};
+
+
+
class JointState
{
public:
@@ -95,17 +118,16 @@
double velocity_;
double applied_effort_;
+ // joint statistics
+ JointStatistics joint_statistics_;
+
// Command
double commanded_effort_;
bool calibrated_;
JointState() : joint_(NULL), position_(0.0), velocity_(0.0), applied_effort_(0.0),
- commanded_effort_(0), calibrated_(false) {}
- JointState(const JointState &s)
- : joint_(s.joint_), position_(s.position_), velocity_(s.velocity_),
- applied_effort_(s.applied_effort_), commanded_effort_(s.commanded_effort_), calibrated_(s.calibrated_)
- {}
+ commanded_effort_(0.0), calibrated_(false){}
};
enum
@@ -119,6 +141,7 @@
JOINT_TYPES_MAX
};
+
}
#endif /* JOINT_H */
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/robot.h
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/robot.h 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/robot.h 2009-09-04 01:06:49 UTC (rev 23803)
@@ -71,7 +71,7 @@
{
public:
/// Constructor
- Robot(HardwareInterface *hw): hw_(hw) {}
+ Robot(HardwareInterface *hw);
/// Destructor
~Robot()
@@ -107,8 +107,10 @@
/// get a transmission pointer based on the transmission name. Returns NULL on failure
Transmission* getTransmission(const std::string &name) const;
+ ros::Time getTime() {return hw_->current_time_;};
+
private:
- HardwareInterface *hw_;
+ HardwareInterface* hw_;
};
@@ -125,7 +127,7 @@
class RobotState
{
public:
- RobotState(Robot *model, HardwareInterface *hw);
+ RobotState(Robot *model);
Robot *model_;
@@ -133,7 +135,7 @@
JointState *getJointState(const std::string &name);
const JointState *getJointState(const std::string &name) const;
- ros::Time getTime() {return hw_->current_time_;};
+ ros::Time getTime() {return model_->getTime();};
/**
* Each transmission refers to the actuators and joints it connects by name.
@@ -151,8 +153,6 @@
void propagateStateBackwards();
void propagateEffortBackwards();
-private:
- HardwareInterface *hw_;
};
}
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/joint.cpp
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/joint.cpp 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/joint.cpp 2009-09-04 01:06:49 UTC (rev 23803)
@@ -150,3 +150,30 @@
return true;
}
+
+void JointStatistics::update(JointState* jnt)
+{
+ if (initialized_){
+ odometer_ += fabs(old_position_ - jnt->position_);
+ if (fabs(jnt->commanded_effort_) > jnt->joint_->effort_limit_)
+ saturated_ = true;
+ min_position_ = fmin(jnt->position_, min_position_);
+ max_position_ = fmax(jnt->position_, max_position_);
+ max_abs_velocity_ = fmax(fabs(jnt->velocity_), max_abs_velocity_);
+ max_abs_effort_ = fmax(fabs(jnt->applied_effort_), max_abs_effort_);
+ }
+ else
+ initialized_ = true;
+ old_position_ = jnt->position_;
+}
+
+
+void JointStatistics::reset()
+{
+ double tmp = min_position_;
+ min_position_ = max_position_;
+ max_position_ = tmp;
+ max_abs_velocity_ = 0.0;
+ max_abs_effort_ = 0.0;
+ saturated_ = false;
+}
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/robot.cpp
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/robot.cpp 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/robot.cpp 2009-09-04 01:06:49 UTC (rev 23803)
@@ -41,14 +41,20 @@
namespace pr2_mechanism {
+
+Robot::Robot(HardwareInterface *hw)
+ :hw_(hw)
+{}
+
+
bool Robot::initXml(TiXmlElement *root)
{
- // Gets the actuator list from the hardware interface
+ // check if current time is valid
if (!hw_){
- ROS_ERROR("Mechanism Model got an invalid pointer to the hardware interface");
+ ROS_ERROR("Mechanism Model received an invalid hardware interface");
return false;
}
- actuators_ = hw_->actuators_;
+ actuators_ = hw_->actuators_;
// Parses the xml into a robot model
urdf::Model robot_description;
@@ -72,7 +78,14 @@
delete jnt;
return false;
}
- joints_.push_back(jnt);
+ // only collect joint types we know about
+ if (jnt->type_ == JOINT_PRISMATIC ||
+ jnt->type_ == JOINT_ROTARY ||
+ jnt->type_ == JOINT_FIXED ||
+ jnt->type_ == JOINT_CONTINUOUS)
+ joints_.push_back(jnt);
+ else
+ delete jnt;
}
// Constructs the transmissions by parsing custom xml.
@@ -100,10 +113,10 @@
transmissions_.push_back(t);
}
-
return true;
}
+
template <class T>
int findIndexByName(const std::vector<T*>& v, const std::string &name)
{
@@ -152,11 +165,10 @@
-RobotState::RobotState(Robot *model, HardwareInterface *hw)
- : model_(model), hw_(hw)
+RobotState::RobotState(Robot *model)
+ : model_(model)
{
assert(model_);
- assert(hw_);
joint_states_.resize(model->joints_.size());
transmissions_in_.resize(model->transmissions_.size());
@@ -180,7 +192,7 @@
{
int index = model_->getActuatorIndex(t->actuator_names_[j]);
assert(index >= 0);
- transmissions_in_[i].push_back(hw_->actuators_[index]);
+ transmissions_in_[i].push_back(model_->actuators_[index]);
}
for (unsigned int j = 0; j < t->joint_names_.size(); ++j)
{
@@ -211,6 +223,11 @@
model_->transmissions_[i]->propagatePosition(transmissions_in_[i],
transmissions_out_[i]);
}
+
+ for (unsigned int i = 0; i < joint_states_.size(); i++)
+ {
+ joint_states_[i].joint_statistics_.update(&(joint_states_[i]));
+ }
}
void RobotState::propagateEffort()
Added: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/ControllerState.msg
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/ControllerState.msg (rev 0)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/ControllerState.msg 2009-09-04 01:06:49 UTC (rev 23803)
@@ -0,0 +1,5 @@
+string name
+byte running
+float64 max_time
+float64 mean_time
+float64 variance_time
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/JointState.msg
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/JointState.msg 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/JointState.msg 2009-09-04 01:06:49 UTC (rev 23803)
@@ -3,4 +3,10 @@
float64 velocity
float64 applied_effort
float64 commanded_effort
-byte is_calibrated
\ No newline at end of file
+byte is_calibrated
+byte saturated
+float64 odometer
+float64 min_position
+float64 max_position
+float64 max_abs_velocity
+float64 max_abs_effort
Modified: pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/MechanismState.msg
===================================================================
--- pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/MechanismState.msg 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_msgs/msg/MechanismState.msg 2009-09-04 01:06:49 UTC (rev 23803)
@@ -1,4 +1,4 @@
Header header
-float64 time # Deprecated. Use the timestamp in the header
ActuatorState[] actuator_states
JointState[] joint_states
+ControllerState[] controller_states
Modified: pkg/trunk/stacks/pr2_simulator/pr2_gazebo_plugins/src/gazebo_mechanism_control.cpp
===================================================================
--- pkg/trunk/stacks/pr2_simulator/pr2_gazebo_plugins/src/gazebo_mechanism_control.cpp 2009-09-04 01:00:00 UTC (rev 23802)
+++ pkg/trunk/stacks/pr2_simulator/pr2_gazebo_plugins/src/gazebo_mechanism_control.cpp 2009-09-04 01:06:49 UTC (rev 23803)
@@ -93,7 +93,7 @@
ReadPr2Xml(node);
// Initializes the fake state (for running the transmissions backwards).
- this->fake_state_ = new pr2_mechanism::RobotState(&this->mc_->model_, &this->hw_);
+ this->fake_state_ = new pr2_mechanism::RobotState(&this->mc_->model_);
// The gazebo joints and mechanism joints should match up.
for (unsigned int i = 0; i < this->mc_->model_.joints_.size(); ++i)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|