Added OdomFrame as parameter..

This commit is contained in:
Konstantinos Chatzilygeroudis 2014-05-17 00:58:48 +03:00
parent 78b3b152b5
commit 10c98dc890
5 changed files with 6 additions and 4 deletions

View File

@ -66,7 +66,7 @@
<joint name="RAnkleRoll" />
</group>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="floating" parent_frame="odom_combined" child_link="base_link" />
<virtual_joint name="virtual_joint" type="floating" parent_frame="odom" child_link="base_link" />
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="virtual_joint" />
<passive_joint name="RHipYawPitch" />

View File

@ -97,7 +97,7 @@
<end_effector name="right_eef" parent_link="RElbowDummy" group="RightHand" parent_group="RightArm" />
<end_effector name="left_eef" parent_link="LElbowDummy" group="LeftHand" parent_group="LeftArm" />
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="floating" parent_frame="odom_combined" child_link="base_link" />
<virtual_joint name="virtual_joint" type="floating" parent_frame="odom" child_link="base_link" />
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="virtual_joint" />
<passive_joint name="RHipYawPitch" />

View File

@ -34,6 +34,7 @@ CameraFrequency: 15
# Robot related parameters
JointPrecision: 0.00174532925
OdomFrame: odom
# DO NOT CHANGE IT
Prefix: nao_dcm

View File

@ -123,7 +123,7 @@ private:
bool sonar_enabled_, tactiles_enabled_, bumpers_enabled_, foot_contacts_enabled_;
bool imu_published_, stiffnesses_enabled_;
int topic_queue_;
string prefix_;
string prefix_, odom_frame_;
double low_freq_, high_freq_, controller_freq_, joint_precision_;
// AL Proxies

View File

@ -504,6 +504,7 @@ void Nao::loadParams()
n_p.param("HighCommunicationFrequency", high_freq_, 100.0);
n_p.param("ControllerFrequency", controller_freq_, 15.0);
n_p.param("JointPrecision", joint_precision_, 0.00174532925);
n_p.param("OdomFrame", odom_frame_, string("odom"));
}
void Nao::brokerDisconnected(const string& event_name, const string &broker_name, const string& subscriber_identifier)
@ -820,7 +821,7 @@ void Nao::publishBaseFootprint(const ros::Time &ts)
{
string odom_frame, l_sole_frame, r_sole_frame, base_link_frame;
try {
odom_frame = base_footprint_listener_.resolve("odom_combined");
odom_frame = base_footprint_listener_.resolve(odom_frame_);
l_sole_frame = base_footprint_listener_.resolve("l_sole");
r_sole_frame = base_footprint_listener_.resolve("r_sole");
base_link_frame = base_footprint_listener_.resolve("base_link");