nodeState
Description
Examples
Optimize Simple Factor Graph
Create a factor graph.
fg = factorGraph;
Define two pose states of the robot as the ground truth.
rstate = [0 0 0; 1 1 pi/2];
Define the relative pose measurement between two nodes from the odometry as the pose difference between the states with some noise. The relative measurement must be in the reference frame of the second node so you must rotate the difference in position to be in the reference frame of the second node.
posediff = diff(rstate);
rotdiffso2 = so2(posediff(3),"theta");
transformedPos = transform(inv(rotdiffso2),posediff(1:2));
odomNoise = 0.1*rand;
measure = [transformedPos posediff(3)] + odomNoise;
Create a factor connecting two SE(2) pose with the relative measurment between the poses. Then add the factor to the factor graph to create two nodes.
ids = generateNodeID(fg,1,"factorTwoPoseSE2");
f = factorTwoPoseSE2(ids,Measurement=measure);
addFactor(fg,f);
Get the state of both pose nodes.
stateDefault = nodeState(fg,ids)
stateDefault = 2×3
0 0 0
0 0 0
Because these nodes are new, they have default state values. Ideally before optimizing, you should assign an approximate guess of the absolute pose. This increases the possibility of the optimize
function finding the global minimum. Otherwise optimize
may become trapped in the local minimum, producing a suboptimal solution.
Keep the first node state at the origin and set the second node state to an approximate xy-position at [0.9 0.95]
and a theta rotation of pi/3
radians. In practical applications you could use sensor measurements from your odometry to determine the approximate state of each pose node.
nodeState(fg,ids(2),[0.9 0.95 pi/3])
ans = 1×3
0.9000 0.9500 1.0472
Before optimizing, save the node state so you can reoptimize as needed.
statePriorOpt1 = nodeState(fg,ids);
Optimize the nodes and check the node states.
optimize(fg); stateOpt1 = nodeState(fg,ids)
stateOpt1 = 2×3
-0.1161 0.9026 0.0571
1.0161 0.0474 1.7094
Note that after optimization the first node did not stay at the origin because although the graph does have the initial guess for the state, the graph does not have any constraint on the absolute position. The graph has only the relative pose measurement, which acts as a constraint for the relative pose between the two nodes. So the graph attempts to reduce the cost related to the relative pose, but not the absolute pose. To provide more information to the graph, you can fix the state of nodes or add an absolute prior measurement factor.
Reset the states and then fix the first node. Then verify that the first node is fixed.
nodeState(fg,ids,statePriorOpt1); fixNode(fg,ids(1)) isNodeFixed(fg,ids(1))
ans = logical
1
Reoptimize the factor graph and get the node states.
optimize(fg)
ans = struct with fields:
InitialCost: 1.9452
FinalCost: 1.9452e-16
NumSuccessfulSteps: 2
NumUnsuccessfulSteps: 0
TotalTime: 8.7976e-05
TerminationType: 0
IsSolutionUsable: 1
OptimizedNodeIDs: 1
FixedNodeIDs: 0
stateOpt2 = nodeState(fg,ids)
stateOpt2 = 2×3
0 0 0
1.0815 -0.9185 1.6523
Note that after optimizing this time, the first node state remained at the origin.
Input Arguments
fg
— Factor graph
factorGraph
object
Factor graph, specified as a factorGraph
object.
nodeIDs
— IDs of nodes to get or set
N-element row vector of nonnegative integers
IDs of the nodes to get or set, specified as an N-element row vector of nonnegative integers. N is the total number of nodes to get or set.
All specified node IDs must specify nodes of the same type.
newStates
— New node states
M-by-N matrix
New node states, specified as an M-by-N
matrix. M is the number of specified IDs and N is
the number of state elements for the specified nodes. Each row of the matrix specifies
the state element values for the corresponding element of
nodeIDs
.
These are the supported node types and the form of their corresponding states:
POSE_SE2
— Pose in SE(2) state space in the form [x y theta]. x and y are the x- and y-positions, respectively, and theta is the orientation.POSE_SE3
— Pose in SE(3) state space in the form [x y z qw qx qy qz]. x, y, and z are the x-, y-, and z-positions, respectively, and qw, qx, qy, and qz represent the orientation as a quaternion.VEL3
— 3-D velocity in the form [vx vy vz]. vx, vy, and vz are the x-, y-, and z-velocities, respectively.POINT_XY
— 2-D point in the form [x y]. x and y are the x- and y-positions, respectively.POINT_XYZ
— 3-D point in the form [x y z]. x, y, and z are the x-, y-, and z-positions, respectively.IMU_BIAS
— IMU gyroscope and accelerometer bias in the form [bias_gyro_x bias_gyro_y bias_gyro_z bias_accel_x bias_accel_y bias_accel_z], where:bias_gyro_x, bias_gyro_y, and bias_gyro_z are the x, y, and z IMU gyroscope biases, respectively.
bias_accel_x, bias_accel_y, and bias_accel_z are the x, y, and z accelerometer biases, respectively.
Output Arguments
state
— State of nodes
M-by-N matrix
State of the nodes, returned as an M-by-N matrix. M is the number of IDs and N is the number of state elements for the specified nodes.
These are the supported node types and the form of their corresponding states:
POSE_SE2
— Pose in SE(2) state space in the form [x y theta]. x and y are the x- and y-positions, respectively, and theta is the orientation.POSE_SE3
— Pose in SE(3) state space in the form [x y z qw qx qy qz]. x, y, and z are the x-, y-, and z-positions, respectively, and qw, qx, qy, and qz represent the orientation as a quaternion.VEL3
— 3-D velocity in the form [vx vy vz]. vx, vy, and vz are the x-, y-, and z-velocities, respectively.POINT_XY
— 2-D point in the form [x y]. x and y are the x- and y-positions, respectively.POINT_XYZ
— 3-D point in the form [x y z]. x, y, and z are the x-, y-, and z-positions, respectively.IMU_BIAS
— IMU gyroscope and accelerometer bias in the form [bias_gyro_x bias_gyro_y bias_gyro_z bias_accel_x bias_accel_y bias_accel_z], where:bias_gyro_x, bias_gyro_y, and bias_gyro_z are the x, y, and z IMU gyroscope biases, respectively.
bias_accel_x, bias_accel_y, and bias_accel_z are the x, y, and z accelerometer biases, respectively.
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
When generating portable C code with a C++ compiler, you must specify hierarchical
packing with non-minimal headers. For more information on packaging options, see the
packNGo
(MATLAB Coder) function.
Version History
Introduced in R2022aR2023a: Get or set multiple nodes at one time
nodeState
now supports getting and setting more than one node at
a time by specifying nodeIDs
as a vector of node IDs.
newStates
also supports additional rows to specify states for
multiple nodes at once.
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)