Skip to content
Snippets Groups Projects
Commit 2ba50445 authored by Joan Vallvé Navarro's avatar Joan Vallvé Navarro
Browse files

move to char keys of states

parent 5e6f96c3
No related branches found
No related tags found
2 merge requests!11new release,!10new release
......@@ -116,8 +116,8 @@ bool WolfRosNode::updateTf()
//Get map2base from Wolf result, and builds base2map pose
tf::Transform T_map2base;
if (current_state.count("P") == 0 or
current_state.count("O") == 0 or
if (current_state.count('P') == 0 or
current_state.count('O') == 0 or
!loc_ts.ok())
{
if (state_available_)
......@@ -137,14 +137,14 @@ bool WolfRosNode::updateTf()
// 2D
if (problem_ptr_->getDim() == 2)
{
T_map2base = tf::Transform (tf::createQuaternionFromYaw(current_state["O"](0)),
tf::Vector3(current_state["P"](0), current_state["P"](1), 0) );
T_map2base = tf::Transform (tf::createQuaternionFromYaw(current_state['O'](0)),
tf::Vector3(current_state['P'](0), current_state['P'](1), 0) );
}
// 3D
else
{
T_map2base = tf::Transform (tf::Quaternion(current_state["O"](0), current_state["O"](1), current_state["O"](2), current_state["O"](3)),
tf::Vector3(current_state["P"](0), current_state["P"](1), current_state["P"](2)) );
T_map2base = tf::Transform (tf::Quaternion(current_state['O'](0), current_state['O'](1), current_state['O'](2), current_state['O'](3)),
tf::Vector3(current_state['P'](0), current_state['P'](1), current_state['P'](2)) );
}
}
......
......@@ -29,8 +29,8 @@ void PublisherPose::publishDerived()
TimeStamp loc_ts = problem_->getTimeStamp();
// state not ready
if (current_state.count("P") == 0 or
current_state.count("O") == 0 or
if (current_state.count('P') == 0 or
current_state.count('O') == 0 or
loc_ts == TimeStamp(0))
{
return;
......@@ -44,23 +44,23 @@ void PublisherPose::publishDerived()
// 2D
if (problem_->getDim() == 2)
{
msg.pose.pose.position.x = current_state["P"](0);
msg.pose.pose.position.y = current_state["P"](1);
msg.pose.pose.position.x = current_state['P'](0);
msg.pose.pose.position.y = current_state['P'](1);
msg.pose.pose.position.z = 0;
msg.pose.pose.orientation = tf::createQuaternionMsgFromYaw(current_state["O"](0));
msg.pose.pose.orientation = tf::createQuaternionMsgFromYaw(current_state['O'](0));
}
// 3D
else
{
msg.pose.pose.position.x = current_state["P"](0);
msg.pose.pose.position.y = current_state["P"](1);
msg.pose.pose.position.z = current_state["P"](2);
msg.pose.pose.position.x = current_state['P'](0);
msg.pose.pose.position.y = current_state['P'](1);
msg.pose.pose.position.z = current_state['P'](2);
msg.pose.pose.orientation.x = current_state["O"](0);
msg.pose.pose.orientation.y = current_state["O"](1);
msg.pose.pose.orientation.z = current_state["O"](2);
msg.pose.pose.orientation.w = current_state["O"](3);
msg.pose.pose.orientation.x = current_state['O'](0);
msg.pose.pose.orientation.y = current_state['O'](1);
msg.pose.pose.orientation.z = current_state['O'](2);
msg.pose.pose.orientation.w = current_state['O'](3);
}
publisher_.publish(msg);
......
......@@ -32,32 +32,32 @@ void Visualizer::initialize(ros::NodeHandle& nh)
nh.param<float>( "frame_color_r", frame_color_.r, 1.0);
nh.param<float>( "frame_color_g", frame_color_.g, 0.8);
nh.param<float>( "frame_color_b", frame_color_.b, 0.0);
nh.param<float>( "frame_color_a", frame_color_.a, 0.5);
nh.param<float>( "frame_color_a", frame_color_.a, 1);
nh.param<float>( "factor_abs_color_r", factor_abs_color_.r, 0.92);
nh.param<float>( "factor_abs_color_g", factor_abs_color_.g, 0.19);
nh.param<float>( "factor_abs_color_b", factor_abs_color_.b, 0.6);
nh.param<float>( "factor_abs_color_a", factor_abs_color_.a, 0.5);
nh.param<float>( "factor_abs_color_a", factor_abs_color_.a, 1);
nh.param<float>( "factor_motion_color_r", factor_motion_color_.r, 1.0);
nh.param<float>( "factor_motion_color_g", factor_motion_color_.g, 1.0);
nh.param<float>( "factor_motion_color_b", factor_motion_color_.b, 0.0);
nh.param<float>( "factor_motion_color_a", factor_motion_color_.a, 0.5);
nh.param<float>( "factor_motion_color_a", factor_motion_color_.a, 1);
nh.param<float>( "factor_loop_color_r", factor_loop_color_.r, 1.0);
nh.param<float>( "factor_loop_color_g", factor_loop_color_.g, 0.0);
nh.param<float>( "factor_loop_color_b", factor_loop_color_.b, 0.0);
nh.param<float>( "factor_loop_color_a", factor_loop_color_.a, 0.5);
nh.param<float>( "factor_loop_color_a", factor_loop_color_.a, 1);
nh.param<float>( "factor_lmk_color_r", factor_lmk_color_.r, 0.0);
nh.param<float>( "factor_lmk_color_g", factor_lmk_color_.g, 0.0);
nh.param<float>( "factor_lmk_color_b", factor_lmk_color_.b, 1.0);
nh.param<float>( "factor_lmk_color_a", factor_lmk_color_.a, 0.5);
nh.param<float>( "factor_lmk_color_a", factor_lmk_color_.a, 1);
nh.param<float>( "factor_geom_color_r", factor_geom_color_.r, 0.0);
nh.param<float>( "factor_geom_color_g", factor_geom_color_.g, 1.0);
nh.param<float>( "factor_geom_color_b", factor_geom_color_.b, 1.0);
nh.param<float>( "factor_geom_color_a", factor_geom_color_.a, 0.5);
nh.param<float>( "factor_geom_color_a", factor_geom_color_.a, 1);
// init markers ---------------------------------------------------
// factor markers message
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment